Skip to content

Commit

Permalink
Franka Panda for MJX.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 682355915
Change-Id: Ice015ce2fc06081e091714dd9fd37c3028b2deb1
  • Loading branch information
btaba authored and copybara-github committed Oct 4, 2024
1 parent e7cb46f commit 9e9185d
Show file tree
Hide file tree
Showing 5 changed files with 347 additions and 1 deletion.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -173,7 +173,7 @@ Menagerie, see [CONTRIBUTING](CONTRIBUTING.md).
| FR3 | Franka Robotics | 7 | [Apache-2.0](franka_fr3/LICENSE) |✖️|
| iiwa14 | KUKA | 7 | [BSD-3-Clause](kuka_iiwa_14/LICENSE) |✖️|
| Lite6 | UFACTORY | 6 | [BSD-3-Clause](ufactory_lite6/LICENSE) |✖️|
| Panda | Franka Robotics | 7 | [BSD-3-Clause](franka_emika_panda/LICENSE) ||
| Panda | Franka Robotics | 7 | [BSD-3-Clause](franka_emika_panda/LICENSE) ||
| Sawyer | Rethink Robotics | 7 | [Apache-2.0](rethink_robotics_sawyer/LICENSE) |✖️|
| Unitree Z1 | Unitree Robotics | 6 | [BSD-3-Clause](unitree_z1/LICENSE) |✖️|
| UR5e | Universal Robots | 6 | [BSD-3-Clause](universal_robots_ur5e/LICENSE) |✖️|
Expand Down
12 changes: 12 additions & 0 deletions franka_emika_panda/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,18 @@ description](https://github.com/frankaemika/franka_ros/tree/develop/franka_descr
position actuator acting on this tendon.
15. Added `scene.xml` which includes the robot, with a textured groundplane, skybox, and haze.

### MJX

A version of the Franka Emika Panda environment was created for MJX. Steps:

1. Added `mjx_panda.xml`, forked from `panda.xml`.
2. Added `mjx_scene.xml` and `mjx_single_cube.xml`, forked from `scene.xml`.
3. Gripper collision geometries were modified to contain less geoms. A capsule collision geom was added to the hand.
4. Solver parameters were tuned for performance.
5. Actuator `kp` and `kv` were reduced for more stable simulation.
6. Added a `site` to the gripper.
7. Removed tendon and added position actuator for the gripper. Changed gripper `ctrlrange`.

## License

This model is released under an [Apache-2.0 License](LICENSE).
276 changes: 276 additions & 0 deletions franka_emika_panda/mjx_panda.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,276 @@
<mujoco model="panda">
<compiler angle="radian" meshdir="assets" autolimits="true"/>

<default>
<default class="panda">
<material specular="0.5" shininess="0.25"/>
<joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/>
<general dyntype="none" biastype="affine" ctrlrange="-2.8973 2.8973" forcerange="-87 87"/>
<position forcerange="-100 100"/>
<default class="finger">
<joint axis="0 1 0" type="slide" range="0 0.04"/>
</default>

<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom group="3" type="mesh" contype="0" conaffinity="0"/>
<default class="primitive_collision">
<geom group="3" type="box" contype="0" conaffinity="0"
condim="3" solimp="0.99 0.995 0.01" solref="0.01 1" friction="1 0.005 0.0001"/>
<default class="fingertip_pad_collision_1">
<geom type="box" size="0.011 0.0075 0.01" pos="0 0.0185 0.011"/>
</default>
<default class="fingertip_pad_collision_2">
<geom type="box" size="0.011 0.0044 0.0019" pos="0 0.0068 0.0022"/>
</default>
<default class="fingertip_pad_collision_3">
<geom type="box" size="0.00875 0.0035 0.01175" pos="0 0.0159 0.02835" quat="1 0.25 0 0"/>
</default>
<default class="fingertip_pad_collision_4">
<geom type="box" size="0.00875 0.0076 0.00825" pos="0 0.00758 0.04525" conaffinity="3"/>
</default>
</default>
</default>
</default>
</default>

<asset>
<material class="panda" name="white" rgba="1 1 1 1"/>
<material class="panda" name="off_white" rgba="0.901961 0.921569 0.929412 1"/>
<material class="panda" name="black" rgba="0.25 0.25 0.25 1"/>
<material class="panda" name="green" rgba="0 1 0 1"/>
<material class="panda" name="light_blue" rgba="0.039216 0.541176 0.780392 1"/>

<!-- Collision meshes -->
<mesh name="link0_c" file="link0.stl"/>
<mesh name="link1_c" file="link1.stl"/>
<mesh name="link2_c" file="link2.stl"/>
<mesh name="link3_c" file="link3.stl"/>
<mesh name="link4_c" file="link4.stl"/>
<mesh name="link5_c0" file="link5_collision_0.obj"/>
<mesh name="link5_c1" file="link5_collision_1.obj"/>
<mesh name="link5_c2" file="link5_collision_2.obj"/>
<mesh name="link6_c" file="link6.stl"/>
<mesh name="link7_c" file="link7.stl"/>
<mesh name="hand_c" file="hand.stl"/>

<!-- Visual meshes -->
<mesh file="link0_0.obj"/>
<mesh file="link0_1.obj"/>
<mesh file="link0_2.obj"/>
<mesh file="link0_3.obj"/>
<mesh file="link0_4.obj"/>
<mesh file="link0_5.obj"/>
<mesh file="link0_7.obj"/>
<mesh file="link0_8.obj"/>
<mesh file="link0_9.obj"/>
<mesh file="link0_10.obj"/>
<mesh file="link0_11.obj"/>
<mesh file="link1.obj"/>
<mesh file="link2.obj"/>
<mesh file="link3_0.obj"/>
<mesh file="link3_1.obj"/>
<mesh file="link3_2.obj"/>
<mesh file="link3_3.obj"/>
<mesh file="link4_0.obj"/>
<mesh file="link4_1.obj"/>
<mesh file="link4_2.obj"/>
<mesh file="link4_3.obj"/>
<mesh file="link5_0.obj"/>
<mesh file="link5_1.obj"/>
<mesh file="link5_2.obj"/>
<mesh file="link6_0.obj"/>
<mesh file="link6_1.obj"/>
<mesh file="link6_2.obj"/>
<mesh file="link6_3.obj"/>
<mesh file="link6_4.obj"/>
<mesh file="link6_5.obj"/>
<mesh file="link6_6.obj"/>
<mesh file="link6_7.obj"/>
<mesh file="link6_8.obj"/>
<mesh file="link6_9.obj"/>
<mesh file="link6_10.obj"/>
<mesh file="link6_11.obj"/>
<mesh file="link6_12.obj"/>
<mesh file="link6_13.obj"/>
<mesh file="link6_14.obj"/>
<mesh file="link6_15.obj"/>
<mesh file="link6_16.obj"/>
<mesh file="link7_0.obj"/>
<mesh file="link7_1.obj"/>
<mesh file="link7_2.obj"/>
<mesh file="link7_3.obj"/>
<mesh file="link7_4.obj"/>
<mesh file="link7_5.obj"/>
<mesh file="link7_6.obj"/>
<mesh file="link7_7.obj"/>
<mesh file="hand_0.obj"/>
<mesh file="hand_1.obj"/>
<mesh file="hand_2.obj"/>
<mesh file="hand_3.obj"/>
<mesh file="hand_4.obj"/>
<mesh file="finger_0.obj"/>
<mesh file="finger_1.obj"/>
</asset>

<worldbody>
<light name="top" pos="0 0 2" mode="trackcom"/>
<body name="link0" childclass="panda">
<inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974"
fullinertia="0.00315 0.00388 0.004285 8.2904e-7 0.00015 8.2299e-6"/>
<geom mesh="link0_0" material="off_white" class="visual"/>
<geom mesh="link0_1" material="black" class="visual"/>
<geom mesh="link0_2" material="off_white" class="visual"/>
<geom mesh="link0_3" material="black" class="visual"/>
<geom mesh="link0_4" material="off_white" class="visual"/>
<geom mesh="link0_5" material="black" class="visual"/>
<geom mesh="link0_7" material="white" class="visual"/>
<geom mesh="link0_8" material="white" class="visual"/>
<geom mesh="link0_9" material="black" class="visual"/>
<geom mesh="link0_10" material="off_white" class="visual"/>
<geom mesh="link0_11" material="white" class="visual"/>
<geom mesh="link0_c" class="collision"/>
<body name="link1" pos="0 0 0.333">
<inertial mass="4.970684" pos="0.003875 0.002081 -0.04762"
fullinertia="0.70337 0.70661 0.0091170 -0.00013900 0.0067720 0.019169"/>
<joint name="joint1" damping="40"/>
<geom material="white" mesh="link1" class="visual"/>
<geom mesh="link1_c" class="collision"/>
<body name="link2" quat="1 -1 0 0">
<inertial mass="0.646926" pos="-0.003141 -0.02872 0.003495"
fullinertia="0.0079620 2.8110e-2 2.5995e-2 -3.925e-3 1.0254e-2 7.04e-4"/>
<joint name="joint2" range="-1.7628 1.7628" damping="40"/>
<geom material="white" mesh="link2" class="visual"/>
<geom mesh="link2_c" class="collision"/>
<body name="link3" pos="0 -0.316 0" quat="1 1 0 0">
<joint name="joint3" damping="40"/>
<inertial mass="3.228604" pos="2.7518e-2 3.9252e-2 -6.6502e-2"
fullinertia="3.7242e-2 3.6155e-2 1.083e-2 -4.761e-3 -1.1396e-2 -1.2805e-2"/>
<geom mesh="link3_0" material="white" class="visual"/>
<geom mesh="link3_1" material="white" class="visual"/>
<geom mesh="link3_2" material="white" class="visual"/>
<geom mesh="link3_3" material="black" class="visual"/>
<geom mesh="link3_c" class="collision"/>
<body name="link4" pos="0.0825 0 0" quat="1 1 0 0">
<inertial mass="3.587895" pos="-5.317e-2 1.04419e-1 2.7454e-2"
fullinertia="2.5853e-2 1.9552e-2 2.8323e-2 7.796e-3 -1.332e-3 8.641e-3"/>
<joint name="joint4" range="-3.0718 -0.0698" damping="40"/>
<geom mesh="link4_0" material="white" class="visual"/>
<geom mesh="link4_1" material="white" class="visual"/>
<geom mesh="link4_2" material="black" class="visual"/>
<geom mesh="link4_3" material="white" class="visual"/>
<geom mesh="link4_c" class="collision"/>
<body name="link5" pos="-0.0825 0.384 0" quat="1 -1 0 0">
<inertial mass="1.225946" pos="-1.1953e-2 4.1065e-2 -3.8437e-2"
fullinertia="3.5549e-2 2.9474e-2 8.627e-3 -2.117e-3 -4.037e-3 2.29e-4"/>
<joint name="joint5" damping="2"/>
<geom mesh="link5_0" material="black" class="visual"/>
<geom mesh="link5_1" material="white" class="visual"/>
<geom mesh="link5_2" material="white" class="visual"/>
<geom mesh="link5_c0" class="collision"/>
<geom mesh="link5_c1" class="collision"/>
<geom mesh="link5_c2" class="collision"/>
<body name="link6" quat="1 1 0 0">
<inertial mass="1.666555" pos="6.0149e-2 -1.4117e-2 -1.0517e-2"
fullinertia="1.964e-3 4.354e-3 5.433e-3 1.09e-4 -1.158e-3 3.41e-4"/>
<joint name="joint6" range="-0.0175 3.7525" damping="2"/>
<geom mesh="link6_0" material="off_white" class="visual"/>
<geom mesh="link6_1" material="white" class="visual"/>
<geom mesh="link6_2" material="black" class="visual"/>
<geom mesh="link6_3" material="white" class="visual"/>
<geom mesh="link6_4" material="white" class="visual"/>
<geom mesh="link6_5" material="white" class="visual"/>
<geom mesh="link6_6" material="white" class="visual"/>
<geom mesh="link6_7" material="light_blue" class="visual"/>
<geom mesh="link6_8" material="light_blue" class="visual"/>
<geom mesh="link6_9" material="black" class="visual"/>
<geom mesh="link6_10" material="black" class="visual"/>
<geom mesh="link6_11" material="white" class="visual"/>
<geom mesh="link6_12" material="green" class="visual"/>
<geom mesh="link6_13" material="white" class="visual"/>
<geom mesh="link6_14" material="black" class="visual"/>
<geom mesh="link6_15" material="black" class="visual"/>
<geom mesh="link6_16" material="white" class="visual"/>
<geom mesh="link6_c" class="collision"/>
<body name="link7" pos="0.088 0 0" quat="1 1 0 0">
<inertial mass="7.35522e-01" pos="1.0517e-2 -4.252e-3 6.1597e-2"
fullinertia="1.2516e-2 1.0027e-2 4.815e-3 -4.28e-4 -1.196e-3 -7.41e-4"/>
<joint name="joint7" damping="2"/>
<geom mesh="link7_0" material="white" class="visual"/>
<geom mesh="link7_1" material="black" class="visual"/>
<geom mesh="link7_2" material="black" class="visual"/>
<geom mesh="link7_3" material="black" class="visual"/>
<geom mesh="link7_4" material="black" class="visual"/>
<geom mesh="link7_5" material="black" class="visual"/>
<geom mesh="link7_6" material="black" class="visual"/>
<geom mesh="link7_7" material="white" class="visual"/>
<geom mesh="link7_c" class="collision"/>
<body name="hand" pos="0 0 0.107" quat="0.9238795 0 0 -0.3826834">
<inertial mass="0.73" pos="-0.01 0 0.03" diaginertia="0.001 0.0025 0.0017"/>
<geom mesh="hand_0" material="off_white" class="visual"/>
<geom mesh="hand_1" material="black" class="visual"/>
<geom mesh="hand_2" material="black" class="visual"/>
<geom mesh="hand_3" material="white" class="visual"/>
<geom mesh="hand_4" material="off_white" class="visual"/>
<geom mesh="hand_c" class="collision"/>
<geom name="hand_capsule" type="capsule"
class="collision" conaffinity="1" size="0.04 0.06"
quat="1 1 0 0" pos="0 0 0.03"/>
<site name="gripper" pos="0 0 0.1"/>
<body name="left_finger" pos="0 0 0.0584">
<inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
<joint name="finger_joint1" class="finger" damping="10"/>
<geom mesh="finger_0" material="off_white" class="visual"/>
<geom mesh="finger_1" material="black" class="visual"/>
<geom mesh="finger_0" class="collision"/>
<geom class="fingertip_pad_collision_1"/>
<geom class="fingertip_pad_collision_2"/>
<geom class="fingertip_pad_collision_3"/>
<geom name="left_finger_pad" class="fingertip_pad_collision_4"/>
</body>
<body name="right_finger" pos="0 0 0.0584" quat="0 0 0 1">
<inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
<joint name="finger_joint2" class="finger" damping="10"/>
<geom mesh="finger_0" material="off_white" class="visual"/>
<geom mesh="finger_1" material="black" class="visual"/>
<geom mesh="finger_0" class="collision"/>
<geom class="fingertip_pad_collision_1"/>
<geom class="fingertip_pad_collision_2"/>
<geom class="fingertip_pad_collision_3"/>
<geom name="right_finger_pad" class="fingertip_pad_collision_4"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<equality>
<joint joint1="finger_joint1" joint2="finger_joint2" solimp="0.95 0.99 0.001" solref="0.005 1"/>
</equality>

<actuator>
<position class="panda" name="actuator1" joint="joint1" kp="1000" kv="20"
ctrlrange="-2.8973 2.8973"/>
<position class="panda" name="actuator2" joint="joint2" kp="1000" kv="20"
ctrlrange="-1.7628 1.7628"/>
<position class="panda" name="actuator3" joint="joint3" kp="750" kv="4"
ctrlrange="-2.8973 2.8973"/>
<position class="panda" name="actuator4" joint="joint4" kp="750" kv="4"
ctrlrange="-3.0718 -0.0698"/>
<position class="panda" name="actuator5" joint="joint5" kp="300" kv="2"
forcerange="-12 12" ctrlrange="-2.8973 2.8973"/>
<position class="panda" name="actuator6" joint="joint6" kp="300" kv="2" forcerange="-12 12"
ctrlrange="-0.0175 3.7525"/>
<position class="panda" name="actuator7" joint="joint7" kp="300" kv="2" forcerange="-12 12"/>
<general class="panda" name="actuator8" joint="finger_joint1"
ctrlrange="0 0.04" gainprm="350 0 0" biasprm="0 -350 -10" forcerange="-200 200"/>
</actuator>
</mujoco>
32 changes: 32 additions & 0 deletions franka_emika_panda/mjx_scene.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<mujoco model="panda scene">
<include file="mjx_panda.xml"/>

<statistic center="0.3 0 0.4" extent="1"/>

<option timestep="0.005" iterations="5" ls_iterations="8" integrator="implicitfast">
<flag eulerdamp="disable"/>
</option>

<custom>
<numeric data="12" name="max_contact_points"/>
</custom>

<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.3 0.3 0.3" specular="0 0 0"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="120" elevation="-20"/>
<scale contactwidth="0.075" contactheight="0.025" forcewidth="0.05" com="0.05" framewidth="0.01" framelength="0.2"/>
</visual>

<asset>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3"
markrgb="0.8 0.8 0.8" width="300" height="300"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
</asset>

<worldbody>
<light pos="0 0 1.5" dir="0 0 -1" directional="true"/>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane" contype="1"/>
</worldbody>
</mujoco>
26 changes: 26 additions & 0 deletions franka_emika_panda/mjx_single_cube.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<mujoco model="panda scene">
<include file="mjx_scene.xml"/>

<worldbody>
<body name="box" pos="0.5 0 0.03">
<freejoint/>
<geom type="box" name="box" size="0.02 0.02 0.03" condim="3"
friction="1 .03 .003" rgba="0 1 0 1" contype="2" conaffinity="1" solref="0.01 1"/>
</body>
<body mocap="true" name="mocap_target">
<geom type="sphere" size="0.025" rgba="1 0 0 1" contype="0" conaffinity="0"/>
</body>
</worldbody>

<keyframe>
<key name="home"
qpos="0 0.3 0 -1.57079 0 2.0 -0.7853 0.04 0.04 0.7 0 0.03 1 0 0 0"
ctrl="0 0.3 0 -1.57079 0 2.0 -0.7853 0.04"/>
<key name="pickup"
qpos="0.2897 0.50732 -0.140016 -2.176 -0.0310497 2.51592 -0.49251 0.04 0.0399982 0.511684 0.0645413 0.0298665 0.665781 2.76848e-17 -2.27527e-17 -0.746147"
ctrl="0.2897 0.423 -0.144392 -2.13105 -0.0291743 2.52586 -0.492492 0.04"/>
<key name="pickup1"
qpos='0.2897 0.496673 -0.142836 -2.14746 -0.0295746 2.52378 -0.492496 0.04 0.0399988 0.529553 0.0731702 0.0299388 0.94209 8.84613e-06 -4.97524e-06 -0.335361'
ctrl="0.2897 0.458 -0.144392 -2.13105 -0.0291743 2.52586 -0.492492 0.04"/>
</keyframe>
</mujoco>

0 comments on commit 9e9185d

Please sign in to comment.