291 lines
18 KiB
XML
Raw Normal View History

<mujoco model="aloha">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<option cone="elliptic" impratio="10"/>
<asset>
<material name="black" rgba="0.15 0.15 0.15 1"/>
<mesh file="vx300s_1_base.stl" scale="0.001 0.001 0.001"/>
<mesh file="vx300s_2_shoulder.stl" scale="0.001 0.001 0.001"/>
<mesh file="vx300s_3_upper_arm.stl" scale="0.001 0.001 0.001"/>
<mesh file="vx300s_4_upper_forearm.stl" scale="0.001 0.001 0.001"/>
<mesh file="vx300s_5_lower_forearm.stl" scale="0.001 0.001 0.001"/>
<mesh file="vx300s_6_wrist.stl" scale="0.001 0.001 0.001"/>
<mesh file="vx300s_7_gripper_prop.stl"/>
<mesh file="vx300s_7_gripper_bar.stl"/>
<mesh file="vx300s_7_gripper_wrist_mount.stl"/>
<mesh file="vx300s_8_custom_finger_left.stl"/>
<mesh file="vx300s_8_custom_finger_right.stl"/>
<mesh file="d405_solid.stl"/>
</asset>
<default>
<default class="vx300s">
<joint axis="0 1 0" actuatorfrcrange="-35 35"/>
<site group="4"/>
<default class="waist">
<joint axis="0 0 1" range="-3.14158 3.14158" damping="5.76"/>
<position ctrlrange="-3.14158 3.14158" kp="43"/>
</default>
<default class="shoulder">
<joint range="-1.85005 1.25664" armature="0.395" frictionloss="2.0" damping="20.0" actuatorfrcrange="-144 144"/>
<position ctrlrange="-1.85005 1.25664" kp="265"/>
</default>
<default class="elbow">
<joint range="-1.76278 1.6057" armature="0.383" frictionloss="1.15" damping="18.49" actuatorfrcrange="-59 59"/>
<position ctrlrange="-1.76278 1.6057" kp="227"/>
</default>
<default class="forearm_roll">
<joint axis="1 0 0" range="-3.14158 3.14158" armature="0.14" damping="6.78" actuatorfrcrange="-22 22"/>
<position ctrlrange="-3.14158 3.14158" kp="78"/>
</default>
<default class="wrist_angle">
<joint range="-1.8675 2.23402" armature="0.008" damping="6.28"/>
<position ctrlrange="-1.8675 2.23402" kp="37"/>
</default>
<default class="wrist_rotate">
<joint axis="1 0 0" range="-3.14158 3.14158" damping="1.2"/>
<position ctrlrange="-3.14158 3.14158" kp="10.4"/>
</default>
<default class="finger">
<joint type="slide" armature="0.243" damping="40"/>
<!--
The joint and control ranges are in meters, representing the linear displacement of the
finger on the rail. Note that the real robot takes in a float value representing the
position of the dynamixel servo, which actuates rotors and moves the fingers along the
the rail. We choose to model the displacement of the finger on the rail instead of the
position of the servo because the former is a more interpretable value.
Some useful values:
Length of rail = 12cm
Width of finger base = 1.9cm
Joint range should be (0.0cm, 4.1cm). This represents the _physical_ limits of the
fingers sliding along the rail. The 0 position represents when the inner edge of
the finger bases are touching each other at exactly the center of the rail.
4.1cm represents the outer edge of the finger bases touching the edge of the rail.
So the value always represents the distance from the inner edge of the finger base
to the center of the rail.
Control range is (0.2cm, 3.7cm). This represents measured values from a real robot
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"/>
<default class="left_finger">
<joint range="0 0.041" axis="0 0 -1"/>
</default>
<default class="right_finger">
<joint range="0 0.041" axis="0 0 -1"/>
</default>
</default>
<default class="visual">
<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"/>
<default class="sphere_collision">
<geom type="sphere" size="0.0006" rgba="1 0 0 1"/>
</default>
</default>
</default>
</default>
<worldbody>
<light mode="targetbodycom" target="left/gripper_link" pos="-.5 .7 2.5" cutoff="55"/>
<light mode="targetbodycom" target="right/gripper_link" pos=".5 .7 2.5" cutoff="55"/>
<camera name="teleoperator_pov" pos="0 -1.354 0.685" xyaxes="1 0 0 0 0.2 .8"/>
<camera name="collaborator_pov" pos="0 1.5 0.8" xyaxes="-1 0 0 0 -0.2 .8"/>
<body name="left/base_link" childclass="vx300s" pos="-0.469 -0.019 0.02">
<inertial pos="-0.0534774 -0.000562575 0.0205961" quat="-0.00292324 0.712517 0.00480387 0.701633" mass="0.969034"
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">
<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">
<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">
<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">
<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">
<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">
<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.13 0 -.003" group="5"/>
<body name="left/gripper_base" euler="0 1.57 -1.57" pos="0.035 0 0">
<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"/>
<geom class="collision" mesh="vx300s_7_gripper_prop"/>
<geom class="visual" mesh="vx300s_7_gripper_bar"/>
<geom class="collision" mesh="vx300s_7_gripper_bar"/>
<geom class="visual" pos="0 -0.03525 -0.0227" quat="0 -1 0 -1" type="mesh" mesh="vx300s_7_gripper_wrist_mount"/>
<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"/>
<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">
<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="collision" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
<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"/>
<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">
<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="collision" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
<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"/>
<site name="left/right_finger" pos="0.015 0.06 0.02"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
<body name="right/base_link" childclass="vx300s" pos="0.469 -0.019 0.02" quat="0 0 0 1">
<inertial pos="-0.0534774 -0.000562575 0.0205961" quat="-0.00292324 0.712517 0.00480387 0.701633" mass="0.969034"
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">
<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">
<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">
<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">
<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">
<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">
<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.13 0 -.003" group="5"/>
<body name="right/gripper_base" euler="0 1.57 -1.57" pos="0.035 0 0">
<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"/>
<geom class="collision" mesh="vx300s_7_gripper_prop"/>
<geom class="visual" mesh="vx300s_7_gripper_bar"/>
<geom class="collision" mesh="vx300s_7_gripper_bar"/>
<geom class="visual" pos="0 -0.03525 -0.0227" quat="0 -0.707107 0 -0.707107" type="mesh" mesh="vx300s_7_gripper_wrist_mount"/>
<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"/>
<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">
<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="collision" quat="1 1 1 -1" type="mesh"
mesh="vx300s_8_custom_finger_left"/>
<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"/>
<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">
<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="collision" quat="1 -1 -1 -1" type="mesh"
mesh="vx300s_8_custom_finger_right"/>
<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"/>
<site name="right/right_finger" pos="0.015 0.06 0.02"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<contact>
<exclude body1="left/base_link" body2="left/shoulder_link"/>
<exclude body1="right/base_link" body2="right/shoulder_link"/>
</contact>
<equality>
<joint joint1="left/left_finger" joint2="left/right_finger" polycoef="0 1 0 0 0"/>
<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"/>
</mujoco>