Skip to content

Commit

Permalink
Changes to inertia inference from meshes.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 726051033
Change-Id: I06252fed680c1e03b8bd72bfca7662f4d3c26bf2
  • Loading branch information
DeepMind authored and copybara-github committed Feb 12, 2025
1 parent 4f89618 commit dcfa5f3
Show file tree
Hide file tree
Showing 4 changed files with 38 additions and 46 deletions.
2 changes: 1 addition & 1 deletion hello_robot_stretch/README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# Hello Robot Stretch 2 Description (MJCF)

Requires MuJoCo 2.3.3 or later.
Requires MuJoCo 3.3.0 or later.

## Overview

Expand Down
34 changes: 15 additions & 19 deletions hello_robot_stretch/stretch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -99,16 +99,16 @@
<material name="Aruco_Shoulder_Sticker" texture="shoulder_aruco_sticker"/>

<mesh file="base_link_0.obj"/>
<mesh file="base_link_2.obj"/>
<mesh file="base_link_2.obj" inertia="shell"/>
<mesh file="base_link_3.obj"/>
<mesh file="base_link_4.obj"/>
<mesh file="base_link_5.obj"/>
<mesh file="base_link_6.obj"/>
<mesh file="base_link_6.obj" inertia="shell"/>
<mesh file="base_link_7.obj"/>
<mesh file="base_link_8.obj"/>
<mesh name="base_link_collision" file="base_link_casterless.stl"/>
<mesh file="link_aruco_right_base.obj"/>
<mesh file="link_aruco_left_base.obj"/>
<mesh file="link_aruco_right_base.obj" inertia="shell"/>
<mesh file="link_aruco_left_base.obj" inertia="shell"/>
<mesh file="respeaker_base.obj"/>
<mesh file="link_mast.obj"/>
<mesh file="link_head_0.obj"/>
Expand All @@ -132,7 +132,7 @@
<mesh file="link_left_wheel_0.obj"/>
<mesh file="link_left_wheel_1.obj"/>
<mesh file="link_lift_0.obj"/>
<mesh file="link_lift_1.obj"/>
<mesh file="link_lift_1.obj" inertia="shell"/>
<mesh file="link_lift_2.obj"/>
<mesh file="link_lift_3.obj"/>
<mesh file="link_lift_4.obj"/>
Expand All @@ -141,7 +141,7 @@
<mesh file="link_lift_7.obj"/>
<mesh file="link_lift_8.obj"/>
<mesh file="link_lift_9.obj"/>
<mesh file="link_aruco_shoulder.obj"/>
<mesh file="link_aruco_shoulder.obj" inertia="shell"/>
<mesh file="link_arm_l4_0.obj"/>
<mesh file="link_arm_l4_1.obj"/>
<mesh file="link_arm_l3_0.obj"/>
Expand All @@ -153,8 +153,8 @@
<mesh file="link_arm_l0_0.obj"/>
<mesh file="link_arm_l0_1.obj"/>
<mesh file="link_arm_l0_2.obj"/>
<mesh file="link_aruco_inner_wrist.obj"/>
<mesh file="link_aruco_top_wrist.obj"/>
<mesh file="link_aruco_inner_wrist.obj" inertia="shell"/>
<mesh file="link_aruco_top_wrist.obj" inertia="shell"/>
<mesh file="laser.obj"/>
<mesh file="link_gripper_fingertip_left.stl"/>
<mesh file="link_gripper_fingertip_right.stl"/>
Expand All @@ -171,11 +171,11 @@
<body name="base_link" childclass="stretch">
<freejoint/>
<geom mesh="base_link_0" material="Caster_Rollers_Red" class="visual"/>
<geom mesh="base_link_2" material="Lightbar_Green" class="visual" shellinertia="true"/>
<geom mesh="base_link_2" material="Lightbar_Green" class="visual"/>
<geom mesh="base_link_3" material="Power_Button_Green" class="visual"/>
<geom mesh="base_link_4" material="USB_Blue" class="visual"/>
<geom mesh="base_link_5" material="Generic_Black" class="visual"/>
<geom mesh="base_link_6" material="Hand_Crush_Sticker" class="visual" shellinertia="true"/>
<geom mesh="base_link_6" material="Hand_Crush_Sticker" class="visual"/>
<geom mesh="base_link_7" material="Pantone_705_U" class="visual"/>
<geom mesh="base_link_8" material="Pantone_Cool_Gray_4_U" class="visual"/>
<geom class="collision" mesh="base_link_collision" mass="15.0"/>
Expand All @@ -200,13 +200,11 @@
<geom mesh="link_head_10" class="collision" mass="0.833027236718691"/>
</body>
<body name="link_aruco_right_base" pos="-0.0015028 -0.130497 0.159748" quat="1 0 0 -1">
<geom material="Aruco_Right_Base_Sticker" mesh="link_aruco_right_base" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Right_Base_Sticker" mesh="link_aruco_right_base" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_right_base" class="collision"/>
</body>
<body name="link_aruco_left_base" pos="-0.0015028 0.130497 0.159748" quat="1 0 0 -1">
<geom material="Aruco_Left_Base_Sticker" mesh="link_aruco_left_base" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Left_Base_Sticker" mesh="link_aruco_left_base" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_left_base" class="collision"/>
</body>
<body name="laser" pos="0.004 0 0.1664" quat="0 0 0 1">
Expand Down Expand Up @@ -277,13 +275,12 @@
<geom mesh="link_arm_l0_1" class="collision"/>
<geom mesh="link_arm_l0_2" class="collision"/>
<body name="link_aruco_top_wrist" pos="0.04725 0.029285 0" quat="0 0 1 1">
<geom material="Aruco_Top_Wrist_Sticker" mesh="link_aruco_top_wrist" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Top_Wrist_Sticker" mesh="link_aruco_top_wrist" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_top_wrist" class="collision"/>
</body>
<body name="link_aruco_inner_wrist" pos="0.04725 -0.0119 -0.02725" quat="0 0 1 0">
<geom material="Aruco_Inner_Wrist_Sticker" mesh="link_aruco_inner_wrist" class="visual"
mass="3.6E-06" shellinertia="true"/>
mass="3.6E-06"/>
<geom mesh="link_aruco_inner_wrist" class="collision"/>
</body>
<body name="link_wrist_yaw" pos="0.083 -0.03075 0" quat="1 1 0 0" gravcomp="1">
Expand Down Expand Up @@ -337,8 +334,7 @@
</body>
</body>
<body name="link_aruco_shoulder" pos="-0.0133769 0.0558541 0.0865" quat="1 0 0 0">
<geom material="Aruco_Shoulder_Sticker" mesh="link_aruco_shoulder" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Shoulder_Sticker" mesh="link_aruco_shoulder" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_shoulder" class="collision"/>
</body>
</body>
Expand Down
2 changes: 1 addition & 1 deletion hello_robot_stretch_3/README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# Hello Robot Stretch 3 Description (MJCF)

> [!IMPORTANT]
> Requires MuJoCo 2.3.3 or later.
> Requires MuJoCo 3.3.0 or later.
## Overview

Expand Down
46 changes: 21 additions & 25 deletions hello_robot_stretch_3/stretch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -123,16 +123,16 @@
<material name="Aruco_gripper_cam_Sticker" texture="gripper_cam_aruco_sticker"/>

<mesh file="base_link_0.obj"/>
<mesh file="base_link_2.obj"/>
<mesh file="base_link_2.obj" inertia="shell"/>
<mesh file="base_link_3.obj"/>
<mesh file="base_link_4.obj"/>
<mesh file="base_link_5.obj"/>
<mesh file="base_link_6.obj"/>
<mesh file="base_link_6.obj" inertia="shell"/>
<mesh file="base_link_7.obj"/>
<mesh file="base_link_8.obj"/>
<mesh name="base_link_collision" file="base_link_casterless.stl"/>
<mesh file="link_aruco_right_base.obj"/>
<mesh file="link_aruco_left_base.obj"/>
<mesh file="link_aruco_right_base.obj" inertia="shell"/>
<mesh file="link_aruco_left_base.obj" inertia="shell"/>
<mesh file="respeaker_base.obj"/>
<mesh file="link_mast.obj"/>
<mesh file="link_head_0.obj"/>
Expand All @@ -156,7 +156,7 @@
<mesh file="link_left_wheel_0.obj"/>
<mesh file="link_left_wheel_1.obj"/>
<mesh file="link_lift_0.obj"/>
<mesh file="link_lift_1.obj"/>
<mesh file="link_lift_1.obj" inertia="shell"/>
<mesh file="link_lift_2.obj"/>
<mesh file="link_lift_3.obj"/>
<mesh file="link_lift_4.obj"/>
Expand All @@ -165,7 +165,7 @@
<mesh file="link_lift_7.obj"/>
<mesh file="link_lift_8.obj"/>
<mesh file="link_lift_9.obj"/>
<mesh file="link_aruco_shoulder.obj"/>
<mesh file="link_aruco_shoulder.obj" inertia="shell"/>
<mesh file="link_arm_l4_0.obj"/>
<mesh file="link_arm_l4_1.obj"/>
<mesh file="link_arm_l3_0.obj"/>
Expand All @@ -177,8 +177,8 @@
<mesh file="link_arm_l0_0.obj"/>
<mesh file="link_arm_l0_1.obj"/>
<mesh file="link_arm_l0_2.obj"/>
<mesh file="link_aruco_inner_wrist.obj"/>
<mesh file="link_aruco_top_wrist.obj"/>
<mesh file="link_aruco_inner_wrist.obj" inertia="shell"/>
<mesh file="link_aruco_top_wrist.obj" inertia="shell"/>
<mesh file="laser.obj"/>
<mesh file="link_gripper_finger_left_0.obj" scale="0.9 1 1"/>
<mesh file="link_gripper_finger_left_1.obj" scale="0.9 1 1"/>
Expand All @@ -192,7 +192,7 @@
<mesh file="link_DW3_wrist_quick_connect.stl"/>
<mesh file="link_DW3_wrist_yaw_bottom.stl"/>
<mesh file="link_SE3_head_nav_cam.stl"/>
<mesh file="link_SG3_aruco_d405.obj"/>
<mesh file="link_SG3_aruco_d405.obj" inertia="shell"/>
<mesh file="link_SG3_gripper_body.obj"/>

<mesh file="link_d405.stl"/>
Expand All @@ -209,8 +209,8 @@

<mesh file="link_SG3_gripper_inner_finger.stl"/>

<mesh file="link_SG3_gripper_left_finger_aruco.obj"/>
<mesh file="link_SG3_gripper_right_finger_aruco.obj"/>
<mesh file="link_SG3_gripper_left_finger_aruco.obj" inertia="shell"/>
<mesh file="link_SG3_gripper_right_finger_aruco.obj" inertia="shell"/>

<mesh file="link_SG3_gripper_right_fingertip.stl"/>
<mesh file="link_SG3_gripper_left_fingertip.stl"/>
Expand All @@ -220,11 +220,11 @@
<body name="base_link" childclass="stretch">
<freejoint/>
<geom mesh="base_link_0" material="Caster_Rollers_Red" class="visual"/>
<geom mesh="base_link_2" material="Lightbar_Green" class="visual" shellinertia="true"/>
<geom mesh="base_link_2" material="Lightbar_Green" class="visual"/>
<geom mesh="base_link_3" material="Power_Button_Green" class="visual"/>
<geom mesh="base_link_4" material="USB_Blue" class="visual"/>
<geom mesh="base_link_5" material="Generic_Black" class="visual"/>
<geom mesh="base_link_6" material="Hand_Crush_Sticker" class="visual" shellinertia="true"/>
<geom mesh="base_link_6" material="Hand_Crush_Sticker" class="visual"/>
<geom mesh="base_link_7" material="Pantone_705_U" class="visual"/>
<geom mesh="base_link_8" material="Pantone_Cool_Gray_4_U" class="visual"/>
<geom class="collision" mesh="base_link_collision" mass="15.0"/>
Expand Down Expand Up @@ -253,13 +253,11 @@
<geom mesh="link_head_10" class="collision" mass="0.833027236718691"/>
</body>
<body name="link_aruco_right_base" pos="-0.0015028 -0.130497 0.159748" quat="1 0 0 -1">
<geom material="Aruco_Right_Base_Sticker" mesh="link_aruco_right_base" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Right_Base_Sticker" mesh="link_aruco_right_base" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_right_base" class="collision"/>
</body>
<body name="link_aruco_left_base" pos="-0.0015028 0.130497 0.159748" quat="1 0 0 -1">
<geom material="Aruco_Left_Base_Sticker" mesh="link_aruco_left_base" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Left_Base_Sticker" mesh="link_aruco_left_base" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_left_base" class="collision"/>
</body>
<body name="laser" pos="0.004 0 0.1664" quat="0 0 0 1">
Expand Down Expand Up @@ -330,13 +328,12 @@
<geom mesh="link_arm_l0_1" class="collision"/>
<geom mesh="link_arm_l0_2" class="collision"/>
<body name="link_aruco_top_wrist" pos="0.04725 0.029285 0" quat="0 0 1 1">
<geom material="Aruco_Top_Wrist_Sticker" mesh="link_aruco_top_wrist" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Top_Wrist_Sticker" mesh="link_aruco_top_wrist" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_top_wrist" class="collision"/>
</body>
<body name="link_aruco_inner_wrist" pos="0.04725 -0.0119 -0.02725" quat="0 0 1 0">
<geom material="Aruco_Inner_Wrist_Sticker" mesh="link_aruco_inner_wrist" class="visual"
mass="3.6E-06" shellinertia="true"/>
mass="3.6E-06"/>
<geom mesh="link_aruco_inner_wrist" class="collision"/>
</body>
<!-- Dex Wrist 3 Tree -->
Expand All @@ -361,7 +358,7 @@
<body name="link_SG3_aruco_d405" pos="0 0.0671264013906604 0.0297716109784749"
euler="-1.397059993 3.139694278 -0.001741181" gravcomp="1">
<geom material="Aruco_gripper_cam_Sticker" mesh="link_SG3_aruco_d405" class="visual"
mass="3.6E-06" shellinertia="true"/>
mass="3.6E-06"/>
<geom mesh="link_SG3_aruco_d405" class="collision"/>
<body name="link_d405" pos="0 -0.03068 0" euler="1.57 0 0">
<geom material="Reflective_Metal" mesh="link_d405" mass="0.29" class="visual"/>
Expand Down Expand Up @@ -405,7 +402,7 @@
<body name="link_SG3_gripper_left_finger_aruco" pos="-0.14425 0.0014877 -0.005189"
euler="0.19199 0.95993 3.1312">
<geom material="Aruco_left_finger_Sticker" mesh="link_SG3_gripper_left_finger_aruco"
class="visual" mass="3.6E-06" shellinertia="true"/>
class="visual" mass="3.6E-06"/>
<geom mesh="link_SG3_gripper_left_finger_aruco" class="collision"/>
</body>
</body>
Expand Down Expand Up @@ -434,7 +431,7 @@
<body name="link_SG3_gripper_right_finger_aruco" pos="0.14426 0 0.005189"
euler="-2.9496 -0.95993 3.1416">
<geom material="Aruco_right_finger_Sticker" mesh="link_SG3_gripper_right_finger_aruco"
class="visual" mass="3.6E-06" shellinertia="true"/>
class="visual" mass="3.6E-06"/>
<geom mesh="link_SG3_gripper_right_finger_aruco" class="collision"/>
</body>
</body>
Expand All @@ -448,8 +445,7 @@
</body>
</body>
<body name="link_aruco_shoulder" pos="-0.0133769 0.0558541 0.0865" quat="1 0 0 0">
<geom material="Aruco_Shoulder_Sticker" mesh="link_aruco_shoulder" class="visual" mass="3.6E-06"
shellinertia="true"/>
<geom material="Aruco_Shoulder_Sticker" mesh="link_aruco_shoulder" class="visual" mass="3.6E-06"/>
<geom mesh="link_aruco_shoulder" class="collision"/>
</body>
</body>
Expand Down

0 comments on commit dcfa5f3

Please sign in to comment.