Skip to content

Commit

Permalink
Updates to Aloha:
Browse files Browse the repository at this point in the history
- Add actuator-based gravity compensation.
- Better collision parameters.
- Improve position of gripper sites.
- Reduce timescale of filter smoothers.
- Add margin/gap to finger collision spheres.

Many of these updates can/should be propagated to the MJX variants, this is left for a future change.

PiperOrigin-RevId: 623806749
Change-Id: I46691d592e17a365960e74ef08901a5c25be0ef7
  • Loading branch information
yuvaltassa authored and copybara-github committed Apr 11, 2024
1 parent 237f849 commit b4cb3de
Show file tree
Hide file tree
Showing 5 changed files with 194 additions and 66 deletions.
2 changes: 1 addition & 1 deletion aloha/README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# ALOHA Description (MJCF)

Requires MuJoCo 3.1.1 or later.
Requires MuJoCo 3.1.4 or later.

## Overview

Expand Down
57 changes: 27 additions & 30 deletions aloha/aloha.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@

<default>
<default class="vx300s">
<joint axis="0 1 0" actuatorfrcrange="-35 35"/>
<joint axis="0 1 0" actuatorfrcrange="-35 35" actuatorgravcomp="true"/>
<site group="4"/>
<default class="waist">
<joint axis="0 0 1" range="-3.14158 3.14158" damping="5.76"/>
Expand Down Expand Up @@ -84,12 +84,9 @@
<geom type="mesh" contype="0" conaffinity="0" density="0" group="2" material="black"/>
</default>
<default class="collision">
<geom group="3" type="mesh"/>
<default class="finger_collision">
<geom condim="4" solimp="2 1 0.01" solref="0.01 1" friction="1 0.005 0.0001"/>
</default>
<geom group="3" type="mesh" condim="6" friction="1 5e-3 5e-4" solref=".01 1"/>
<default class="sphere_collision">
<geom type="sphere" size="0.0006" rgba="1 0 0 1"/>
<geom type="sphere" size="0.0006" rgba="1 0 0 1" margin=".015" gap=".015"/>
</default>
</default>
</default>
Expand All @@ -106,42 +103,42 @@
diaginertia="0.0071633 0.00602451 0.00169819"/>
<geom quat="1 0 0 1" class="visual" mesh="vx300s_1_base"/>
<geom quat="1 0 0 1" mesh="vx300s_1_base" class="collision"/>
<body name="left/shoulder_link" pos="0 0 0.079">
<body name="left/shoulder_link" pos="0 0 0.079" gravcomp="1">
<inertial pos="0.000259233 -3.3552e-06 0.0116129" quat="-0.476119 0.476083 0.52279 0.522826" mass="0.798614"
diaginertia="0.00120156 0.00113744 0.0009388"/>
<joint name="left/waist" class="waist"/>
<geom pos="0 0 -0.003" quat="1 0 0 1" class="visual" mesh="vx300s_2_shoulder"/>
<geom pos="0 0 -0.003" quat="1 0 0 1" mesh="vx300s_2_shoulder" class="collision"/>
<body name="left/upper_arm_link" pos="0 0 0.04805">
<body name="left/upper_arm_link" pos="0 0 0.04805" gravcomp="1">
<inertial pos="0.0206949 4e-10 0.226459" quat="0 0.0728458 0 0.997343" mass="0.792592"
diaginertia="0.00911338 0.008925 0.000759317"/>
<joint name="left/shoulder" class="shoulder"/>
<geom quat="1 0 0 1" class="visual" mesh="vx300s_3_upper_arm"/>
<geom quat="1 0 0 1" class="collision" mesh="vx300s_3_upper_arm"/>
<body name="left/upper_forearm_link" pos="0.05955 0 0.3">
<body name="left/upper_forearm_link" pos="0.05955 0 0.3" gravcomp="1">
<inertial pos="0.105723 0 0" quat="-0.000621631 0.704724 0.0105292 0.709403" mass="0.322228"
diaginertia="0.00144107 0.00134228 0.000152047"/>
<joint name="left/elbow" class="elbow"/>
<geom class="visual" mesh="vx300s_4_upper_forearm"/>
<geom class="collision" mesh="vx300s_4_upper_forearm"/>
<body name="left/lower_forearm_link" pos="0.2 0 0">
<body name="left/lower_forearm_link" pos="0.2 0 0" gravcomp="1">
<inertial pos="0.0513477 0.00680462 0" quat="-0.702604 -0.0796724 -0.702604 0.0796724" mass="0.414823"
diaginertia="0.0005911 0.000546493 0.000155707"/>
<joint name="left/forearm_roll" class="forearm_roll"/>
<geom quat="0 1 0 0" class="visual" mesh="vx300s_5_lower_forearm"/>
<geom quat="0 1 0 0" class="collision" mesh="vx300s_5_lower_forearm"/>
<body name="left/wrist_link" pos="0.1 0 0">
<body name="left/wrist_link" pos="0.1 0 0" gravcomp="1">
<inertial pos="0.046743 -7.6652e-06 0.010565" quat="-0.00100191 0.544586 0.0026583 0.8387"
mass="0.115395" diaginertia="5.45707e-05 4.63101e-05 4.32692e-05"/>
<joint name="left/wrist_angle" class="wrist_angle"/>
<geom quat="1 0 0 1" class="visual" mesh="vx300s_6_wrist"/>
<geom quat="1 0 0 1" class="collision" mesh="vx300s_6_wrist"/>
<body name="left/gripper_link" pos="0.069744 0 0">
<body name="left/gripper_link" pos="0.069744 0 0" gravcomp="1">
<inertial pos="0.0395662 -2.56311e-07 0.00400649" quat="0.62033 0.619916 -0.339682 0.339869"
mass="0.251652" diaginertia="0.000689546 0.000650316 0.000468142"/>
<joint name="left/wrist_rotate" class="wrist_rotate"/>
<site name="left/gripper" pos="0.15 0 0" group="5"/>
<body name="left/gripper_base" euler="0 1.57 -1.57" pos="0.035 0 0">
<site name="left/gripper" pos="0.13 0 -.003" group="5"/>
<body name="left/gripper_base" euler="0 1.57 -1.57" pos="0.035 0 0" gravcomp="1">
<inertial pos="0.000182154 -0.0341589 -0.0106026" quat="0.435286 0.557074 -0.551539 0.442718"
mass="0.42158" diaginertia="0.00110438 0.000790537 0.000469727"/>
<geom class="visual" mesh="vx300s_7_gripper_prop"/>
Expand All @@ -153,26 +150,26 @@
<geom class="visual" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<geom class="collision" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<camera name="wrist_cam_left" pos="0 -0.0824748 -0.0095955" fovy="58" mode="fixed" euler="2.70525955359 0 0"/>
<body name="left/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
<body name="left/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1" gravcomp="1">
<inertial pos="0.0143478 -0.0284791 0.0122897" quat="0.535486 0.458766 -0.450407 0.547651"
mass="0.0862937" diaginertia="5.86848e-05 4.46887e-05 1.8397e-05"/>
<joint name="left/left_finger" class="left_finger"/>
<geom pos="0.0141637 0.0211727 0.06" class="visual" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
<geom pos="0.0141637 0.0211727 0.06" class="finger_collision" quat="1 1 1 -1" type="mesh"
<geom pos="0.0141637 0.0211727 0.06" class="collision" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
<geom pos="0.013 -0.0892 0.0268" class="sphere_collision"/>
<geom pos="0.0222 -0.0892 0.0268" class="sphere_collision"/>
<geom pos="0.0182 -0.0845 0.0266" class="sphere_collision"/>
<site name="left/left_finger" pos="0.015 -0.06 0.02"/>
</body>
<body name="left/right_finger_link" pos="-0.0191 -0.0141637 0.0211727" quat="1 1 1 1">
<body name="left/right_finger_link" pos="-0.0191 -0.0141637 0.0211727" quat="1 1 1 1" gravcomp="1">
<inertial pos="0.0143711 0.0284792 0.0121421" quat="0.461317 0.537615 -0.545478 0.447894"
mass="0.0862932" diaginertia="5.86828e-05 4.46887e-05 1.83949e-05"/>
<joint name="left/right_finger" class="right_finger"/>
<geom pos="0.0141637 -0.0211727 0.0597067" class="visual" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
<geom pos="0.0141637 -0.0211727 0.0597067" class="finger_collision" quat="1 -1 -1 -1" type="mesh"
<geom pos="0.0141637 -0.0211727 0.0597067" class="collision" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
<geom pos="0.013 0.0892 0.0268" class="sphere_collision"/>
<geom pos="0.0222 0.0892 0.0268" class="sphere_collision"/>
Expand All @@ -193,42 +190,42 @@
diaginertia="0.0071633 0.00602451 0.00169819"/>
<geom quat="1 0 0 1" class="visual" mesh="vx300s_1_base"/>
<geom quat="1 0 0 1" mesh="vx300s_1_base" class="collision"/>
<body name="right/shoulder_link" pos="0 0 0.079">
<body name="right/shoulder_link" pos="0 0 0.079" gravcomp="1">
<inertial pos="0.000259233 -3.3552e-06 0.0116129" quat="-0.476119 0.476083 0.52279 0.522826" mass="0.798614"
diaginertia="0.00120156 0.00113744 0.0009388"/>
<joint name="right/waist" class="waist"/>
<geom pos="0 0 -0.003" quat="1 0 0 1" class="visual" mesh="vx300s_2_shoulder"/>
<geom pos="0 0 -0.003" quat="1 0 0 1" mesh="vx300s_2_shoulder" class="collision"/>
<body name="right/upper_arm_link" pos="0 0 0.04805">
<body name="right/upper_arm_link" pos="0 0 0.04805" gravcomp="1">
<inertial pos="0.0206949 4e-10 0.226459" quat="0 0.0728458 0 0.997343" mass="0.792592"
diaginertia="0.00911338 0.008925 0.000759317"/>
<joint name="right/shoulder" class="shoulder"/>
<geom quat="1 0 0 1" class="visual" mesh="vx300s_3_upper_arm"/>
<geom quat="1 0 0 1" class="collision" mesh="vx300s_3_upper_arm"/>
<body name="right/upper_forearm_link" pos="0.05955 0 0.3">
<body name="right/upper_forearm_link" pos="0.05955 0 0.3" gravcomp="1">
<inertial pos="0.105723 0 0" quat="-0.000621631 0.704724 0.0105292 0.709403" mass="0.322228"
diaginertia="0.00144107 0.00134228 0.000152047"/>
<joint name="right/elbow" class="elbow"/>
<geom class="visual" mesh="vx300s_4_upper_forearm"/>
<geom class="collision" mesh="vx300s_4_upper_forearm"/>
<body name="right/lower_forearm_link" pos="0.2 0 0">
<body name="right/lower_forearm_link" pos="0.2 0 0" gravcomp="1">
<inertial pos="0.0513477 0.00680462 0" quat="-0.702604 -0.0796724 -0.702604 0.0796724" mass="0.414823"
diaginertia="0.0005911 0.000546493 0.000155707"/>
<joint name="right/forearm_roll" class="forearm_roll"/>
<geom quat="0 1 0 0" class="visual" mesh="vx300s_5_lower_forearm"/>
<geom quat="0 1 0 0" class="collision" mesh="vx300s_5_lower_forearm"/>
<body name="right/wrist_link" pos="0.1 0 0">
<body name="right/wrist_link" pos="0.1 0 0" gravcomp="1">
<inertial pos="0.046743 -7.6652e-06 0.010565" quat="-0.00100191 0.544586 0.0026583 0.8387"
mass="0.115395" diaginertia="5.45707e-05 4.63101e-05 4.32692e-05"/>
<joint name="right/wrist_angle" class="wrist_angle"/>
<geom quat="1 0 0 1" class="visual" mesh="vx300s_6_wrist"/>
<geom quat="1 0 0 1" class="collision" mesh="vx300s_6_wrist"/>
<body name="right/gripper_link" pos="0.069744 0 0">
<body name="right/gripper_link" pos="0.069744 0 0" gravcomp="1">
<inertial pos="0.0395662 -2.56311e-07 0.00400649" quat="0.62033 0.619916 -0.339682 0.339869"
mass="0.251652" diaginertia="0.000689546 0.000650316 0.000468142"/>
<joint name="right/wrist_rotate" class="wrist_rotate"/>
<site name="right/gripper" pos="0.15 0 0" group="5"/>
<body name="right/gripper_base" euler="0 1.57 -1.57" pos="0.035 0 0">
<site name="right/gripper" pos="0.13 0 -.003" group="5"/>
<body name="right/gripper_base" euler="0 1.57 -1.57" pos="0.035 0 0" gravcomp="1">
<inertial pos="0.000182154 -0.0341589 -0.0106026" quat="0.435286 0.557074 -0.551539 0.442718"
mass="0.42158" diaginertia="0.00110438 0.000790537 0.000469727"/>
<geom class="visual" mesh="vx300s_7_gripper_prop"/>
Expand All @@ -240,26 +237,26 @@
<geom class="visual" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<geom class="collision" pos="0 -0.0824748 -0.0095955" quat="0 0 -0.21644 -0.976296" type="mesh" mesh="d405_solid"/>
<camera name="wrist_cam_right" pos="0 -0.0824748 -0.0095955" fovy="58" mode="fixed" euler="2.70525955359 0 0"/>
<body name="right/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
<body name="right/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1" gravcomp="1">
<inertial pos="0.0143478 -0.0284791 0.0122897" quat="0.535486 0.458766 -0.450407 0.547651"
mass="0.0862937" diaginertia="5.86848e-05 4.46887e-05 1.8397e-05"/>
<joint name="right/left_finger" class="left_finger"/>
<geom pos="0.0141637 0.0211727 0.06" class="visual" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
<geom pos="0.0141637 0.0211727 0.06" class="finger_collision" quat="1 1 1 -1" type="mesh"
<geom pos="0.0141637 0.0211727 0.06" class="collision" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
<geom pos="0.013 -0.0892 0.0268" class="sphere_collision"/>
<geom pos="0.0222 -0.0892 0.0268" class="sphere_collision"/>
<geom pos="0.0182 -0.0845 0.0266" class="sphere_collision"/>
<site name="right/left_finger" pos="0.015 -0.06 0.02"/>
</body>
<body name="right/right_finger_link" pos="-0.0191 -0.0141637 0.0211727" quat="1 1 1 1">
<body name="right/right_finger_link" pos="-0.0191 -0.0141637 0.0211727" quat="1 1 1 1" gravcomp="1">
<inertial pos="0.0143711 0.0284792 0.0121421" quat="0.461317 0.537615 -0.545478 0.447894"
mass="0.0862932" diaginertia="5.86828e-05 4.46887e-05 1.83949e-05"/>
<joint name="right/right_finger" class="right_finger"/>
<geom pos="0.0141637 -0.0211727 0.0597067" class="visual" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
<geom pos="0.0141637 -0.0211727 0.0597067" class="finger_collision" quat="1 -1 -1 -1" type="mesh"
<geom pos="0.0141637 -0.0211727 0.0597067" class="collision" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
<geom pos="0.013 0.0892 0.0268" class="sphere_collision"/>
<geom pos="0.0222 0.0892 0.0268" class="sphere_collision"/>
Expand Down
6 changes: 3 additions & 3 deletions aloha/integrated_cartesian_actuators.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,11 @@ as specified in the main model. -->
<default>
<default class="act">
<!-- filtered actuators produce smoother motion -->
<general dyntype="filterexact" biastype="affine" dynprm="1"/>
<general dyntype="filterexact" biastype="affine" dynprm="0.5"/>
<default class="act_position">
<general gainprm="1000" biasprm="0 -1000 -300"/>
<default class="act_position_x">
<general ctrlrange="-0.45 0.2"/>
<general ctrlrange="-0.5 0.2"/>
</default>
<default class="act_position_y">
<general ctrlrange="-0.35 0.35"/>
Expand All @@ -24,7 +24,7 @@ as specified in the main model. -->
<general gainprm="50" biasprm="0 -50 -15" ctrlrange="-1.3 1.3"/>
</default>
<default class="act_gripper">
<general ctrlrange="0.002 0.037" gainprm="2000" biasprm="0 -2000 -124" dynprm="0.1"/>
<general ctrlrange="0.002 0.037" gainprm="2000" biasprm="0 -2000 -124" dynprm="0.3"/>
</default>
</default>
</default>
Expand Down
Loading

0 comments on commit b4cb3de

Please sign in to comment.