Skip to content

Commit

Permalink
Update stretch to work with mujoco 3.3.0.
Browse files Browse the repository at this point in the history
  • Loading branch information
kevinzakka committed Mar 5, 2025
1 parent f80ecf9 commit 340436b
Show file tree
Hide file tree
Showing 5 changed files with 658 additions and 55 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@ All notable changes to this project will be documented in this file.

- Improved ALOHA example script.
- Fixed a small bug in the exit criterion of the ALOHA example script.
- Updated Stretch example to work with MuJoCo >= 3.3.0.

## [0.0.5] - 2024-09-27

Expand Down
113 changes: 59 additions & 54 deletions examples/apptronik_apollo/apollo.xml
Original file line number Diff line number Diff line change
@@ -1,31 +1,29 @@
<mujoco model="apptronik_apollo">
<compiler angle="radian" meshdir="assets/"/>
<compiler angle="radian" meshdir="assets"/>

<option timestep="0.005" integrator="implicitfast"/>

<size nkey="1"/>

<default>
<site rgba="1 0 0 1" size="0.01" group="5"/>
<joint limited="true"/>
<geom contype="0" conaffinity="0" condim="1" group="1" solref="0.005" margin="0.0005"/>
<light diffuse="0.8 0.8 0.8"/>

<equality solref="0.005" solimp="0.99 0.999 1e-05"/>
<default class="active_adhesion">
<geom margin="0.01" gap="0.01" rgba="0.8 0.5 0.5 1"/>
</default>
<default class="visual">
<geom type="mesh"/>
<default class="visual_dark">
<geom rgba="0.0980392 0.0980392 0.0980392 1"/>
<default class="apollo">
<site rgba="1 0 0 1" size="0.01" group="5"/>
<joint limited="true"/>
<geom contype="0" conaffinity="0" condim="1" group="1" solref="0.005" margin="0.0005"/>
<equality solref="0.005" solimp="0.99 0.999 1e-05"/>
<default class="active_adhesion">
<geom margin="0.01" gap="0.01" rgba="0.8 0.5 0.5 1"/>
</default>
<default class="visual_light">
<geom rgba="0.960784 0.960784 0.952941 1"/>
<default class="visual">
<geom type="mesh"/>
<default class="visual_dark">
<geom rgba="0.0980392 0.0980392 0.0980392 1"/>
</default>
<default class="visual_light">
<geom rgba="0.960784 0.960784 0.952941 1"/>
</default>
</default>
<default class="collision">
<geom contype="1" conaffinity="1" group="3" rgba="0 1 0 0.4"/>
</default>
</default>
<default class="collision">
<geom group="3" rgba="0 1 0 0.4" contype="1" conaffinity="1"/>
</default>
</default>

Expand Down Expand Up @@ -78,7 +76,7 @@

<worldbody>
<light pos="0 0 3" dir="0 0 -1" diffuse="0.2 0.2 0.2" mode="trackcom"/>
<body name="base_link" pos="0 0 1.0813">
<body name="base_link" pos="0 0 1.0813" childclass="apollo">
<inertial pos="-0.0466459 -2.50736e-05 -0.0721416" quat="0.661991 0.662086 0.248682 -0.248127" mass="7.43582" diaginertia="0.0633318 0.0512326 0.0281854"/>
<joint name="floating_base" type="free" limited="false" actuatorfrclimited="false"/>
<geom class="visual_light" mesh="pelvis_link"/>
Expand Down Expand Up @@ -307,39 +305,46 @@
<body name="world_link"/>
</worldbody>

<contact>
<exclude body1="r_wrist_pitch_link" body2="r_wrist_roll_link"/>
<exclude body1="r_shoulder_fe_link" body2="r_wrist_roll_link"/>
<exclude body1="l_wrist_pitch_link" body2="l_wrist_roll_link"/>
<exclude body1="l_shoulder_fe_link" body2="l_wrist_roll_link"/>
</contact>

<actuator>
<general name="neck_yaw" joint="neck_yaw" ctrlrange="-1.65806 1.65806" forcerange="-10.6 10.6" biastype="affine" gainprm="28" biasprm="0 -28 -15"/>
<general name="neck_roll" joint="neck_roll" ctrlrange="-0.785398 0.785398" forcerange="-34.2 34.2" biastype="affine" gainprm="9" biasprm="0 -9 -3"/>
<general name="neck_pitch" joint="neck_pitch" ctrlrange="-0.261799 0.523599" forcerange="-34.2 34.2" biastype="affine" gainprm="8" biasprm="0 -8 -3"/>
<general name="torso_pitch" joint="torso_pitch" ctrlrange="-0.305433 1.35263" forcerange="-315 315" biastype="affine" gainprm="1525" biasprm="0 -1525 -142"/>
<general name="torso_roll" joint="torso_roll" ctrlrange="-0.20944 0.20944" forcerange="-414 414" biastype="affine" gainprm="2052" biasprm="0 -2052 -165"/>
<general name="torso_yaw" joint="torso_yaw" ctrlrange="-0.829031 0.829031" forcerange="-120 120" biastype="affine" gainprm="600" biasprm="0 -600 -60"/>
<general name="l_hip_ie" joint="l_hip_ie" ctrlrange="-0.567232 1.09083" forcerange="-120 120" biastype="affine" gainprm="595" biasprm="0 -595 -171"/>
<general name="l_hip_aa" joint="l_hip_aa" ctrlrange="-0.218166 0.741765" forcerange="-494 494" biastype="affine" gainprm="1880" biasprm="0 -1880 -153"/>
<general name="l_hip_fe" joint="l_hip_fe" ctrlrange="-1.85005 0.476475" forcerange="-342 342" biastype="affine" gainprm="1047" biasprm="0 -1047 -92"/>
<general name="l_knee_fe" joint="l_knee_fe" ctrlrange="0 2.61799" forcerange="-336 336" biastype="affine" gainprm="606" biasprm="0 -606 -46"/>
<general name="l_ankle_ie" joint="l_ankle_ie" ctrlrange="-0.654498 0.305433" forcerange="-120 120" biastype="affine" gainprm="420" biasprm="0 -420 -11"/>
<general name="l_ankle_pd" joint="l_ankle_pd" ctrlrange="-1.5708 0.436332" forcerange="-150 150" biastype="affine" gainprm="882" biasprm="0 -882 -21"/>
<general name="r_hip_ie" joint="r_hip_ie" ctrlrange="-1.09083 0.567232" forcerange="-120 120" biastype="affine" gainprm="595" biasprm="0 -595 -171"/>
<general name="r_hip_aa" joint="r_hip_aa" ctrlrange="-0.741765 0.218166" forcerange="-494 494" biastype="affine" gainprm="1880" biasprm="0 -1880 -153"/>
<general name="r_hip_fe" joint="r_hip_fe" ctrlrange="-1.85005 0.476475" forcerange="-342 342" biastype="affine" gainprm="1047" biasprm="0 -1047 -92"/>
<general name="r_knee_fe" joint="r_knee_fe" ctrlrange="0 2.61799" forcerange="-336 336" biastype="affine" gainprm="606" biasprm="0 -606 -46"/>
<general name="r_ankle_ie" joint="r_ankle_ie" ctrlrange="-0.305433 0.654498" forcerange="-120 120" biastype="affine" gainprm="420" biasprm="0 -420 -11"/>
<general name="r_ankle_pd" joint="r_ankle_pd" ctrlrange="-1.5708 0.436332" forcerange="-150 150" biastype="affine" gainprm="882" biasprm="0 -882 -21"/>
<general name="l_shoulder_aa" joint="l_shoulder_aa" ctrlrange="-0.122173 1.6057" forcerange="-78 78" biastype="affine" gainprm="395" biasprm="0 -395 -26"/>
<general name="l_shoulder_ie" joint="l_shoulder_ie" ctrlrange="-0.471239 0.471239" forcerange="-67 67" biastype="affine" gainprm="530" biasprm="0 -530 -45"/>
<general name="l_shoulder_fe" joint="l_shoulder_fe" ctrlrange="-2.18166 0.610865" forcerange="-114 114" biastype="affine" gainprm="277" biasprm="0 -277 -21"/>
<general name="l_elbow_fe" joint="l_elbow_fe" ctrlrange="-2.61799 0.174533" forcerange="-114 114" biastype="affine" gainprm="312" biasprm="0 -312 -24"/>
<general name="l_wrist_roll" joint="l_wrist_roll" ctrlrange="-1.65806 1.65806" forcerange="-10.6 10.6" biastype="affine" gainprm="47" biasprm="0 -47 -15"/>
<general name="l_wrist_yaw" joint="l_wrist_yaw" ctrlrange="-0.785398 0.785398" forcerange="-34.2 34.2" biastype="affine" gainprm="20" biasprm="0 -20 -3"/>
<general name="l_wrist_pitch" joint="l_wrist_pitch" ctrlrange="-0.837758 1.67552" forcerange="-34.2 34.2" biastype="affine" gainprm="18" biasprm="0 -18 -3"/>
<general name="r_shoulder_aa" joint="r_shoulder_aa" ctrlrange="-1.6057 0.122173" forcerange="-78 78" biastype="affine" gainprm="395" biasprm="0 -395 -26"/>
<general name="r_shoulder_ie" joint="r_shoulder_ie" ctrlrange="-0.471239 0.471239" forcerange="-67 67" biastype="affine" gainprm="530" biasprm="0 -530 -45"/>
<general name="r_shoulder_fe" joint="r_shoulder_fe" ctrlrange="-2.18166 0.610865" forcerange="-114 114" biastype="affine" gainprm="277" biasprm="0 -277 -21"/>
<general name="r_elbow_fe" joint="r_elbow_fe" ctrlrange="-2.61799 0.174533" forcerange="-114 114" biastype="affine" gainprm="312" biasprm="0 -312 -24"/>
<general name="r_wrist_roll" joint="r_wrist_roll" ctrlrange="-1.65806 1.65806" forcerange="-10.6 10.6" biastype="affine" gainprm="47" biasprm="0 -47 -15"/>
<general name="r_wrist_yaw" joint="r_wrist_yaw" ctrlrange="-0.785398 0.785398" forcerange="-34.2 34.2" biastype="affine" gainprm="20" biasprm="0 -20 -3"/>
<general name="r_wrist_pitch" joint="r_wrist_pitch" ctrlrange="-1.67552 0.837758" forcerange="-34.2 34.2" biastype="affine" gainprm="18" biasprm="0 -18 -3"/>
<general class="apollo" name="neck_yaw" joint="neck_yaw" ctrlrange="-1.65806 1.65806" forcerange="-10.6 10.6" biastype="affine" gainprm="28" biasprm="0 -28 -15"/>
<general class="apollo" name="neck_roll" joint="neck_roll" ctrlrange="-0.785398 0.785398" forcerange="-34.2 34.2" biastype="affine" gainprm="9" biasprm="0 -9 -3"/>
<general class="apollo" name="neck_pitch" joint="neck_pitch" ctrlrange="-0.261799 0.523599" forcerange="-34.2 34.2" biastype="affine" gainprm="8" biasprm="0 -8 -3"/>
<general class="apollo" name="torso_pitch" joint="torso_pitch" ctrlrange="-0.305433 1.35263" forcerange="-315 315" biastype="affine" gainprm="1525" biasprm="0 -1525 -142"/>
<general class="apollo" name="torso_roll" joint="torso_roll" ctrlrange="-0.20944 0.20944" forcerange="-414 414" biastype="affine" gainprm="2052" biasprm="0 -2052 -165"/>
<general class="apollo" name="torso_yaw" joint="torso_yaw" ctrlrange="-0.829031 0.829031" forcerange="-120 120" biastype="affine" gainprm="600" biasprm="0 -600 -60"/>
<general class="apollo" name="l_hip_ie" joint="l_hip_ie" ctrlrange="-0.567232 1.09083" forcerange="-120 120" biastype="affine" gainprm="595" biasprm="0 -595 -171"/>
<general class="apollo" name="l_hip_aa" joint="l_hip_aa" ctrlrange="-0.218166 0.741765" forcerange="-494 494" biastype="affine" gainprm="1880" biasprm="0 -1880 -153"/>
<general class="apollo" name="l_hip_fe" joint="l_hip_fe" ctrlrange="-1.85005 0.476475" forcerange="-342 342" biastype="affine" gainprm="1047" biasprm="0 -1047 -92"/>
<general class="apollo" name="l_knee_fe" joint="l_knee_fe" ctrlrange="0 2.61799" forcerange="-336 336" biastype="affine" gainprm="606" biasprm="0 -606 -46"/>
<general class="apollo" name="l_ankle_ie" joint="l_ankle_ie" ctrlrange="-0.654498 0.305433" forcerange="-120 120" biastype="affine" gainprm="420" biasprm="0 -420 -11"/>
<general class="apollo" name="l_ankle_pd" joint="l_ankle_pd" ctrlrange="-1.5708 0.436332" forcerange="-150 150" biastype="affine" gainprm="882" biasprm="0 -882 -21"/>
<general class="apollo" name="r_hip_ie" joint="r_hip_ie" ctrlrange="-1.09083 0.567232" forcerange="-120 120" biastype="affine" gainprm="595" biasprm="0 -595 -171"/>
<general class="apollo" name="r_hip_aa" joint="r_hip_aa" ctrlrange="-0.741765 0.218166" forcerange="-494 494" biastype="affine" gainprm="1880" biasprm="0 -1880 -153"/>
<general class="apollo" name="r_hip_fe" joint="r_hip_fe" ctrlrange="-1.85005 0.476475" forcerange="-342 342" biastype="affine" gainprm="1047" biasprm="0 -1047 -92"/>
<general class="apollo" name="r_knee_fe" joint="r_knee_fe" ctrlrange="0 2.61799" forcerange="-336 336" biastype="affine" gainprm="606" biasprm="0 -606 -46"/>
<general class="apollo" name="r_ankle_ie" joint="r_ankle_ie" ctrlrange="-0.305433 0.654498" forcerange="-120 120" biastype="affine" gainprm="420" biasprm="0 -420 -11"/>
<general class="apollo" name="r_ankle_pd" joint="r_ankle_pd" ctrlrange="-1.5708 0.436332" forcerange="-150 150" biastype="affine" gainprm="882" biasprm="0 -882 -21"/>
<general class="apollo" name="l_shoulder_aa" joint="l_shoulder_aa" ctrlrange="-0.122173 1.6057" forcerange="-78 78" biastype="affine" gainprm="395" biasprm="0 -395 -26"/>
<general class="apollo" name="l_shoulder_ie" joint="l_shoulder_ie" ctrlrange="-0.471239 0.471239" forcerange="-67 67" biastype="affine" gainprm="530" biasprm="0 -530 -45"/>
<general class="apollo" name="l_shoulder_fe" joint="l_shoulder_fe" ctrlrange="-2.18166 0.610865" forcerange="-114 114" biastype="affine" gainprm="277" biasprm="0 -277 -21"/>
<general class="apollo" name="l_elbow_fe" joint="l_elbow_fe" ctrlrange="-2.61799 0.174533" forcerange="-114 114" biastype="affine" gainprm="312" biasprm="0 -312 -24"/>
<general class="apollo" name="l_wrist_roll" joint="l_wrist_roll" ctrlrange="-1.65806 1.65806" forcerange="-10.6 10.6" biastype="affine" gainprm="47" biasprm="0 -47 -15"/>
<general class="apollo" name="l_wrist_yaw" joint="l_wrist_yaw" ctrlrange="-0.785398 0.785398" forcerange="-34.2 34.2" biastype="affine" gainprm="20" biasprm="0 -20 -3"/>
<general class="apollo" name="l_wrist_pitch" joint="l_wrist_pitch" ctrlrange="-0.837758 1.67552" forcerange="-34.2 34.2" biastype="affine" gainprm="18" biasprm="0 -18 -3"/>
<general class="apollo" name="r_shoulder_aa" joint="r_shoulder_aa" ctrlrange="-1.6057 0.122173" forcerange="-78 78" biastype="affine" gainprm="395" biasprm="0 -395 -26"/>
<general class="apollo" name="r_shoulder_ie" joint="r_shoulder_ie" ctrlrange="-0.471239 0.471239" forcerange="-67 67" biastype="affine" gainprm="530" biasprm="0 -530 -45"/>
<general class="apollo" name="r_shoulder_fe" joint="r_shoulder_fe" ctrlrange="-2.18166 0.610865" forcerange="-114 114" biastype="affine" gainprm="277" biasprm="0 -277 -21"/>
<general class="apollo" name="r_elbow_fe" joint="r_elbow_fe" ctrlrange="-2.61799 0.174533" forcerange="-114 114" biastype="affine" gainprm="312" biasprm="0 -312 -24"/>
<general class="apollo" name="r_wrist_roll" joint="r_wrist_roll" ctrlrange="-1.65806 1.65806" forcerange="-10.6 10.6" biastype="affine" gainprm="47" biasprm="0 -47 -15"/>
<general class="apollo" name="r_wrist_yaw" joint="r_wrist_yaw" ctrlrange="-0.785398 0.785398" forcerange="-34.2 34.2" biastype="affine" gainprm="20" biasprm="0 -20 -3"/>
<general class="apollo" name="r_wrist_pitch" joint="r_wrist_pitch" ctrlrange="-1.67552 0.837758" forcerange="-34.2 34.2" biastype="affine" gainprm="18" biasprm="0 -18 -3"/>
</actuator>

<sensor>
Expand Down
43 changes: 43 additions & 0 deletions examples/hello_robot_stretch_3/scene_33.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
<mujoco model="stretch scene">
<include file="stretch_33.xml"/>

<statistic center="0 0 .75" extent="1.2" meansize="0.05"/>

<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"/>
</visual>

<asset>
<material name="floor" rgba=".1 .1 .1 1" reflectance="0.1"/>
<texture type="2d" name="wood" file="wood.png"/>
<material name="wood" texture="wood"/>
<material name="object" rgba=".2 .2 .2 1"/>
<texture type="skybox" builtin="gradient" rgb1="0.44 0.80 1.00" rgb2="1 1 1" width="512" height="3072"/>
</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="floor"/>
<!-- <body name="table" pos="0 -1 .24">
<geom type="box" size=".6 .5 .24" mass="1" material="wood"/>
</body> -->
<!-- <body name="object1" pos="-.02 -0.55 .6">
<freejoint/>
<geom type="box" size=".02 .04 .04" mass=".5" rgba=".2 .2 .5 1"/>
</body> -->
<!-- <body name="object2" pos=".08 -0.55 .6">
<freejoint/>
<geom type="cylinder" size=".02 .04 .04" mass=".5" rgba=".8 .2 .2 1"/>
</body> -->
<body name="base_target" pos="0.5 0 .5" mocap="true">
<geom type="sphere" size=".08" contype="0" conaffinity="0" rgba=".6 .3 .3 .2"/>
<site type="sphere" size="0.01" rgba="0 0 1 1" group="1"/>
</body>
<body name="EE_target" pos="0.5 0 .5" quat="0 1 0 0" mocap="true">
<geom type="box" size=".05 .05 .05" contype="0" conaffinity="0" rgba=".6 .3 .3 .2"/>
<site type="sphere" size="0.01" rgba="0 0 1 1" group="1"/>
</body>
</worldbody>
</mujoco>
Loading

0 comments on commit 340436b

Please sign in to comment.