More merge conflicts. Taking main changes then will integrate mine.
124 lines
8.5 KiB
Diff
124 lines
8.5 KiB
Diff
--- 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">
|
|
- <geom group="3" type="mesh" condim="6" friction="1 5e-3 5e-4" solref=".01 1"/>
|
|
+ <geom group="4" type="mesh" contype="0" conaffinity="0"/>
|
|
+ <default class="finger_collision">
|
|
+ <geom condim="3" solimp="0.99 0.995 0.01" solref="0.01 1" friction="1 0.005 0.0001"/>
|
|
+ </default>
|
|
<default class="sphere_collision">
|
|
<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"
|
|
+ condim="3" solref="0.01 1" friction="1 0.005 0.0001"/>
|
|
+ </default>
|
|
</default>
|
|
</default>
|
|
</default>
|
|
@@ -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 +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"/>
|
|
- <geom pos="0.0141637 0.0211727 0.06" class="collision" quat="1 1 1 -1" type="mesh"
|
|
+ <geom pos="0.0141637 0.0211727 0.06" class="finger_collision" quat="1 1 1 -1" type="mesh"
|
|
mesh="vx300s_8_custom_finger_left"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="-0.01 -0.0192 0.015 0.015 -0.0852 0.0228" class="primitive_collision"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="0.035 -0.0192 0.015 0.02 -0.0852 0.0228" class="primitive_collision"/>
|
|
<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 +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"/>
|
|
- <geom pos="0.0141637 -0.0211727 0.0597067" class="collision" quat="1 -1 -1 -1" type="mesh"
|
|
+ <geom pos="0.0141637 -0.0211727 0.0597067" class="finger_collision" quat="1 -1 -1 -1" type="mesh"
|
|
mesh="vx300s_8_custom_finger_right"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="-0.01 0.0192 0.015 0.015 0.0852 0.0228" class="primitive_collision"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="0.035 -0.0192 0.015 0.02 0.0852 0.0228" class="primitive_collision"/>
|
|
<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 +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 +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"/>
|
|
- <geom pos="0.0141637 0.0211727 0.06" class="collision" quat="1 1 1 -1" type="mesh"
|
|
+ <geom pos="0.0141637 0.0211727 0.06" class="finger_collision" quat="1 1 1 -1" type="mesh"
|
|
mesh="vx300s_8_custom_finger_left"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="-0.01 -0.0192 0.015 0.015 -0.0852 0.0228" class="primitive_collision"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="0.035 -0.0192 0.015 0.02 -0.0852 0.0228" class="primitive_collision"/>
|
|
<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 +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"/>
|
|
- <geom pos="0.0141637 -0.0211727 0.0597067" class="collision" quat="1 -1 -1 -1" type="mesh"
|
|
+ <geom pos="0.0141637 -0.0211727 0.0597067" class="finger_collision" quat="1 -1 -1 -1" type="mesh"
|
|
mesh="vx300s_8_custom_finger_right"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="-0.01 0.0192 0.015 0.015 0.0852 0.0228" class="primitive_collision"/>
|
|
+ <geom pos="0 0 0" type="capsule" size="0.005" fromto="0.035 -0.0192 0.015 0.02 0.0852 0.0228" class="primitive_collision"/>
|
|
<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 +307,5 @@
|
|
<joint joint1="right/left_finger" joint2="right/right_finger" polycoef="0 1 0 0 0"/>
|
|
</equality>
|
|
|
|
- <include file="joint_position_actuators.xml"/>
|
|
- <include file="keyframe_ctrl.xml"/>
|
|
+ <include file="mjx_filtered_cartesian_actuators.xml"/>
|
|
</mujoco>
|