Skip to content

Commit

Permalink
Revert to more stable values for mjx Aloha.
Browse files Browse the repository at this point in the history
PiperOrigin-RevId: 678787966
Change-Id: Ibc6ac695b1ada3f496983f89368bdde0e8295294
  • Loading branch information
btaba authored and copybara-github committed Sep 25, 2024
1 parent 98b2634 commit e7cb46f
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 15 deletions.
53 changes: 42 additions & 11 deletions aloha/mjx_aloha.patch
Original file line number Diff line number Diff line change
@@ -1,6 +1,36 @@
--- aloha.xml 2024-07-24 19:38:17.000000000 +0100
+++ mjx_aloha.xml 2024-09-17 10:18:25.000000000 +0100
@@ -84,10 +84,16 @@
--- aloha.xml 2024-07-24 11:38:17.000000000 -0700
+++ mjx_aloha.xml 2024-09-25 11:33:18.000000000 -0700
@@ -1,7 +1,11 @@
<mujoco model="aloha">
<compiler angle="radian" meshdir="assets" autolimits="true"/>

- <option cone="elliptic" impratio="10"/>
+ <option impratio="5"/>
+
+ <visual>
+ <scale contactwidth="0.075" contactheight="0.025" forcewidth="0.05"/>
+ </visual>

<asset>
<material name="black" rgba="0.15 0.15 0.15 1"/>
@@ -21,6 +25,7 @@
</asset>

<default>
+ <mesh maxhullvert="32"/>
<default class="vx300s">
<joint axis="0 1 0" actuatorfrcrange="-35 35"/>
<site group="4"/>
@@ -72,7 +77,7 @@
where the gripper is actuated to its fully closed and fully open positions. Therefore the
control range represents limits enforced by _software_ on the real robot.
-->
- <position ctrlrange="0.002 0.037" kp="2000" kv="124"/>
+ <position ctrlrange="0.002 0.037" kp="365"/>
<default class="left_finger">
<joint range="0 0.041" axis="0 0 -1"/>
</default>
@@ -84,10 +89,17 @@
<geom type="mesh" mass="0" group="2" material="black" contype="0" conaffinity="0"/>
</default>
<default class="collision">
Expand All @@ -13,20 +43,21 @@
<geom type="sphere" size="0.0006" rgba="1 0 0 1"/>
</default>
+ <default class="primitive_collision">
+ <geom contype="0" conaffinity="1" rgba="1 0 0 0.5" group="3"/>
+ <geom contype="0" conaffinity="1" rgba="1 0 0 0.5" group="3"
+ condim="3" solref="0.01 1" friction="1 0.005 0.0001"/>
+ </default>
</default>
</default>
</default>
@@ -149,6 +155,7 @@
@@ -149,6 +161,7 @@
<geom class="collision" pos="0 -0.03525 -0.0227" quat="0 -1 0 -1" type="mesh" mesh="vx300s_7_gripper_wrist_mount"/>
<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"/>
+ <geom class="primitive_collision" type="capsule" fromto="0.055 0 0.015 -0.055 0 0.015" size="0.03" />
<camera name="wrist_cam_left" pos="0 -0.0824748 -0.0095955" mode="fixed" euler="2.70525955359 0 0"
focal="1.93e-3 1.93e-3" resolution="1280 720" sensorsize="3896e-6 2140e-6"/>
<body name="left/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
@@ -157,8 +164,10 @@
@@ -157,8 +170,10 @@
<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"/>
Expand All @@ -38,7 +69,7 @@
<geom name="left/left_g0" pos="0.013 -0.0892 0.0268" class="sphere_collision"/>
<geom name="left/left_g1" pos="0.0222 -0.0892 0.0268" class="sphere_collision"/>
<geom name="left/left_g2" pos="0.0182 -0.0845 0.0266" class="sphere_collision"/>
@@ -170,8 +179,10 @@
@@ -170,8 +185,10 @@
<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"/>
Expand All @@ -50,15 +81,15 @@
<geom name="left/right_g0" pos="0.013 0.0892 0.0268" class="sphere_collision"/>
<geom name="left/right_g1" pos="0.0222 0.0892 0.0268" class="sphere_collision"/>
<geom name="left/right_g2" pos="0.0182 0.0845 0.0266" class="sphere_collision"/>
@@ -237,6 +248,7 @@
@@ -237,6 +254,7 @@
<geom class="collision" pos="0 -0.03525 -0.0227" quat="0 -0.707107 0 -0.707107" type="mesh" mesh="vx300s_7_gripper_wrist_mount"/>
<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"/>
+ <geom class="primitive_collision" type="capsule" fromto="0.055 0 0.015 -0.055 0 0.015" size="0.03" />
<camera name="wrist_cam_right" pos="0 -0.0824748 -0.0095955" mode="fixed" euler="2.70525955359 0 0"
focal="1.93e-3 1.93e-3" resolution="1280 720" sensorsize="3896e-6 2140e-6"/>
<body name="right/left_finger_link" pos="0.0191 -0.0141637 0.0211727" quat="1 -1 -1 1">
@@ -245,8 +257,10 @@
@@ -245,8 +263,10 @@
<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"/>
Expand All @@ -70,7 +101,7 @@
<geom name="right/left_g0" pos="0.013 -0.0892 0.0268" class="sphere_collision"/>
<geom name="right/left_g1" pos="0.0222 -0.0892 0.0268" class="sphere_collision"/>
<geom name="right/left_g2" pos="0.0182 -0.0845 0.0266" class="sphere_collision"/>
@@ -258,8 +272,10 @@
@@ -258,8 +278,10 @@
<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"/>
Expand All @@ -82,7 +113,7 @@
<geom name="right/right_g0" pos="0.013 0.0892 0.0268" class="sphere_collision"/>
<geom name="right/right_g1" pos="0.0222 0.0892 0.0268" class="sphere_collision"/>
<geom name="right/right_g2" pos="0.0182 0.0845 0.0266" class="sphere_collision"/>
@@ -285,6 +301,5 @@
@@ -285,6 +307,5 @@
<joint joint1="right/left_finger" joint2="right/right_finger" polycoef="0 1 0 0 0"/>
</equality>

Expand Down
8 changes: 4 additions & 4 deletions aloha/mjx_scene.patch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
--- scene.xml 2024-07-24 11:01:16.000000000 -0700
+++ mjx_scene.xml 2024-07-24 11:01:09.000000000 -0700
--- scene.xml 2024-07-24 11:38:17.000000000 -0700
+++ mjx_scene.xml 2024-09-25 10:13:59.000000000 -0700
@@ -1,7 +1,13 @@
<mujoco model="aloha_scene">
<compiler meshdir="assets" texturedir="assets"/>
Expand All @@ -8,10 +8,10 @@
+ <include file="mjx_aloha.xml"/>
+
+ <custom>
+ <numeric data="8" name="max_contact_points"/>
+ <numeric data="12" name="max_contact_points"/>
+ </custom>
+
+ <option iterations="8" ls_iterations="8" timestep="0.01"/>
+ <option iterations="8" ls_iterations="8" timestep="0.005"/>

<statistic center="0 -0.1 0.2" extent="0.6" meansize="0.05"/>

Expand Down

0 comments on commit e7cb46f

Please sign in to comment.