316 lines
18 KiB
XML
316 lines
18 KiB
XML
|
<mujoco model="tidybot">
|
||
|
<compiler angle="radian" meshdir="assets"/>
|
||
|
|
||
|
<option integrator="implicitfast"/>
|
||
|
<option cone="elliptic" impratio="10"/>
|
||
|
|
||
|
<default>
|
||
|
<default class="base">
|
||
|
<default class="base/visual">
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
|
||
|
</default>
|
||
|
<default class="base/collision">
|
||
|
<geom type="mesh" group="3"/>
|
||
|
</default>
|
||
|
</default>
|
||
|
|
||
|
<default class="gen3">
|
||
|
<default class="gen3/visual">
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="2" rgba="0.75294 0.75294 0.75294 1"/>
|
||
|
</default>
|
||
|
<default class="gen3/collision">
|
||
|
<geom type="mesh" group="3"/>
|
||
|
</default>
|
||
|
<default class="large_actuator">
|
||
|
<position kp="2000" kv="100" forcerange="-105 105"/>
|
||
|
</default>
|
||
|
<default class="small_actuator">
|
||
|
<position kp="500" kv="50" forcerange="-52 52"/>
|
||
|
</default>
|
||
|
</default>
|
||
|
|
||
|
<default class="2f85">
|
||
|
<mesh scale="0.001 0.001 0.001"/>
|
||
|
<general biastype="affine"/>
|
||
|
|
||
|
<joint axis="1 0 0"/>
|
||
|
<default class="driver">
|
||
|
<joint range="0 0.8" armature="0.005" damping="0.1" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
|
||
|
</default>
|
||
|
<default class="follower">
|
||
|
<joint range="-0.872664 0.872664" armature="0.001" pos="0 -0.018 0.0065" solimplimit="0.95 0.99 0.001"
|
||
|
solreflimit="0.005 1"/>
|
||
|
</default>
|
||
|
<default class="spring_link">
|
||
|
<joint range="-0.29670597283 0.8" armature="0.001" stiffness="0.05" springref="2.62" damping="0.00125"/>
|
||
|
</default>
|
||
|
<default class="coupler">
|
||
|
<joint range="-1.57 0" armature="0.001" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
|
||
|
</default>
|
||
|
|
||
|
<default class="2f85/visual">
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
|
||
|
</default>
|
||
|
<default class="2f85/collision">
|
||
|
<geom type="mesh" group="3"/>
|
||
|
<default class="pad_box1">
|
||
|
<geom mass="0" type="box" pos="0 -0.0026 0.028125" size="0.011 0.004 0.009375" friction="0.7"
|
||
|
solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.55 0.55 0.55 1"/>
|
||
|
</default>
|
||
|
<default class="pad_box2">
|
||
|
<geom mass="0" type="box" pos="0 -0.0026 0.009375" size="0.011 0.004 0.009375" friction="0.6"
|
||
|
solimp="0.95 0.99 0.001" solref="0.004 1" priority="1" rgba="0.45 0.45 0.45 1"/>
|
||
|
</default>
|
||
|
</default>
|
||
|
</default>
|
||
|
|
||
|
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
|
||
|
</default>
|
||
|
|
||
|
<asset>
|
||
|
<material name="black" rgba="0.11372549 0.11372549 0.10196078 1"/>
|
||
|
<material name="gray" rgba="0.62745098 0.65098039 0.64705882 1"/>
|
||
|
<material name="dark_gray" rgba="0.35294118 0.37647059 0.37254902 1"/>
|
||
|
<mesh file="base/bumper.stl"/>
|
||
|
<mesh file="base/bottom_plate.stl"/>
|
||
|
<mesh file="base/body.stl"/>
|
||
|
<mesh file="base/top_plate.stl"/>
|
||
|
<mesh file="base/arm_plate.stl"/>
|
||
|
|
||
|
<mesh name="gen3/base_link" file="gen3/base_link.stl"/>
|
||
|
<mesh name="shoulder_link" file="gen3/shoulder_link.stl"/>
|
||
|
<mesh name="half_arm_1_link" file="gen3/half_arm_1_link.stl"/>
|
||
|
<mesh name="half_arm_2_link" file="gen3/half_arm_2_link.stl"/>
|
||
|
<mesh name="forearm_link" file="gen3/forearm_link.stl"/>
|
||
|
<mesh name="spherical_wrist_1_link" file="gen3/spherical_wrist_1_link.stl"/>
|
||
|
<mesh name="spherical_wrist_2_link" file="gen3/spherical_wrist_2_link.stl"/>
|
||
|
<mesh name="bracelet_with_vision_link" file="gen3/bracelet_with_vision_link.stl"/>
|
||
|
|
||
|
<material name="metal" rgba="0.58 0.58 0.58 1"/>
|
||
|
<material name="silicone" rgba="0.1882 0.1882 0.1882 1"/>
|
||
|
<material name="2f85/gray" rgba="0.4627 0.4627 0.4627 1"/>
|
||
|
<material name="2f85/black" rgba="0.149 0.149 0.149 1"/>
|
||
|
<mesh class="2f85" file="2f85/base.stl"/>
|
||
|
<mesh class="2f85" file="2f85/driver.stl"/>
|
||
|
<mesh class="2f85" file="2f85/coupler.stl"/>
|
||
|
<mesh class="2f85" file="2f85/follower.stl"/>
|
||
|
<mesh class="2f85" file="2f85/pad.stl"/>
|
||
|
<mesh class="2f85" file="2f85/silicone_pad.stl"/>
|
||
|
<mesh class="2f85" file="2f85/spring_link.stl"/>
|
||
|
</asset>
|
||
|
|
||
|
<worldbody>
|
||
|
<body name="base_link">
|
||
|
<inertial pos="0 0 0.035" mass="60" diaginertia="0.001 0.001 0.001"/>
|
||
|
<joint name="joint_x" type="slide" axis="1 0 0"/>
|
||
|
<joint name="joint_y" type="slide" axis="0 1 0"/>
|
||
|
<joint name="joint_th"/>
|
||
|
<geom class="base/visual" mesh="bumper" material="black"/>
|
||
|
<geom class="base/visual" mesh="bottom_plate" material="dark_gray"/>
|
||
|
<geom class="base/visual" mesh="body" material="gray"/>
|
||
|
<geom class="base/visual" mesh="top_plate" material="dark_gray"/>
|
||
|
<geom class="base/visual" mesh="arm_plate" material="gray"/>
|
||
|
<geom class="base/collision" mesh="bumper"/>
|
||
|
<geom class="base/collision" mesh="bottom_plate"/>
|
||
|
<geom class="base/collision" mesh="body"/>
|
||
|
<geom class="base/collision" mesh="top_plate"/>
|
||
|
<geom class="base/collision" mesh="arm_plate"/>
|
||
|
<camera name="base" pos="0.2525 0 0.335" euler="0 -0.7853981634 -1.5707963268" fovy="52.23384539951277"
|
||
|
resolution="640 360"/>
|
||
|
<body name="gen3/base_link" pos="0 0 0.335" quat="1 0 0 0">
|
||
|
<inertial pos="-0.000648 -0.000166 0.084487" quat="0.999294 0.00139618 -0.0118387 0.035636" mass="1.697"
|
||
|
diaginertia="0.00462407 0.00449437 0.00207755"/>
|
||
|
<geom class="gen3/visual" mesh="gen3/base_link"/>
|
||
|
<geom class="gen3/collision" mesh="gen3/base_link"/>
|
||
|
<body name="shoulder_link" pos="0 0 0.15643" quat="0 1 0 0">
|
||
|
<inertial pos="-2.3e-05 -0.010364 -0.07336" quat="0.707051 0.0451246 -0.0453544 0.704263" mass="1.3773"
|
||
|
diaginertia="0.00488868 0.00457 0.00135132"/>
|
||
|
<joint name="joint_1"/>
|
||
|
<geom class="gen3/visual" mesh="shoulder_link"/>
|
||
|
<geom class="gen3/collision" mesh="shoulder_link"/>
|
||
|
<body name="half_arm_1_link" pos="0 0.005375 -0.12838" quat="1 1 0 0">
|
||
|
<inertial pos="-4.4e-05 -0.09958 -0.013278" quat="0.482348 0.516286 -0.516862 0.483366" mass="1.1636"
|
||
|
diaginertia="0.0113017 0.011088 0.00102532"/>
|
||
|
<joint name="joint_2" range="-2.24 2.24"/>
|
||
|
<geom class="gen3/visual" mesh="half_arm_1_link"/>
|
||
|
<geom class="gen3/collision" mesh="half_arm_1_link"/>
|
||
|
<body name="half_arm_2_link" pos="0 -0.21038 -0.006375" quat="1 -1 0 0">
|
||
|
<inertial pos="-4.4e-05 -0.006641 -0.117892" quat="0.706144 0.0213722 -0.0209128 0.707437" mass="1.1636"
|
||
|
diaginertia="0.0111633 0.010932 0.00100671"/>
|
||
|
<joint name="joint_3"/>
|
||
|
<geom class="gen3/visual" mesh="half_arm_2_link"/>
|
||
|
<geom class="gen3/collision" mesh="half_arm_2_link"/>
|
||
|
<body name="forearm_link" pos="0 0.006375 -0.21038" quat="1 1 0 0">
|
||
|
<inertial pos="-1.8e-05 -0.075478 -0.015006" quat="0.483678 0.515961 -0.515859 0.483455" mass="0.9302"
|
||
|
diaginertia="0.00834839 0.008147 0.000598606"/>
|
||
|
<joint name="joint_4" range="-2.57 2.57"/>
|
||
|
<geom class="gen3/visual" mesh="forearm_link"/>
|
||
|
<geom class="gen3/collision" mesh="forearm_link"/>
|
||
|
<body name="spherical_wrist_1_link" pos="0 -0.20843 -0.006375" quat="1 -1 0 0">
|
||
|
<inertial pos="1e-06 -0.009432 -0.063883" quat="0.703558 0.0707492 -0.0707492 0.703558" mass="0.6781"
|
||
|
diaginertia="0.00165901 0.001596 0.000346988"/>
|
||
|
<joint name="joint_5"/>
|
||
|
<geom class="gen3/visual" mesh="spherical_wrist_1_link"/>
|
||
|
<geom class="gen3/collision" mesh="spherical_wrist_1_link"/>
|
||
|
<body name="spherical_wrist_2_link" pos="0 0.00017505 -0.10593" quat="1 1 0 0">
|
||
|
<inertial pos="1e-06 -0.045483 -0.00965" quat="0.44426 0.550121 -0.550121 0.44426" mass="0.6781"
|
||
|
diaginertia="0.00170087 0.001641 0.00035013"/>
|
||
|
<joint name="joint_6" range="-2.09 2.09"/>
|
||
|
<geom class="gen3/visual" mesh="spherical_wrist_2_link"/>
|
||
|
<geom class="gen3/collision" mesh="spherical_wrist_2_link"/>
|
||
|
<body name="bracelet_link" pos="0 -0.10593 -0.00017505" quat="1 -1 0 0">
|
||
|
<inertial pos="0.000281 0.011402 -0.029798" quat="0.394358 0.596779 -0.577293 0.393789" mass="0.5"
|
||
|
diaginertia="0.000657336 0.000587019 0.000320645"/>
|
||
|
<joint name="joint_7"/>
|
||
|
<geom class="gen3/visual" mesh="bracelet_with_vision_link"/>
|
||
|
<geom class="gen3/collision" mesh="bracelet_with_vision_link"/>
|
||
|
<body name="base" pos="0 0 -0.06149039" quat="0 -1 1 0" childclass="2f85">
|
||
|
<inertial mass="0.777441" pos="0 -2.70394e-05 0.0354675" quat="1 -0.00152849 0 0"
|
||
|
diaginertia="0.000260285 0.000225381 0.000152708"/>
|
||
|
<geom class="2f85/visual" mesh="base" material="2f85/black"/>
|
||
|
<geom class="2f85/collision" mesh="base"/>
|
||
|
<!-- <site name="pinch" pos="0 0 0.145" type="sphere" group="5" rgba="0.9 0.9 0.9 1"
|
||
|
size="0.005"/> -->
|
||
|
<!-- Right-hand side 4-bar linkage -->
|
||
|
<body name="right_driver" pos="0 0.0306011 0.054904">
|
||
|
<inertial mass="0.00899563" pos="2.96931e-12 0.0177547 0.00107314"
|
||
|
quat="0.681301 0.732003 0 0" diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
|
||
|
<joint name="right_driver_joint" class="driver"/>
|
||
|
<geom class="2f85/visual" mesh="driver" material="2f85/gray"/>
|
||
|
<geom class="2f85/collision" mesh="driver"/>
|
||
|
<body name="right_coupler" pos="0 0.0315 -0.0041">
|
||
|
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175"
|
||
|
quat="0.705636 -0.0455904 0.0455904 0.705636"
|
||
|
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
|
||
|
<joint name="right_coupler_joint" class="coupler"/>
|
||
|
<geom class="2f85/visual" mesh="coupler" material="2f85/black"/>
|
||
|
<geom class="2f85/collision" mesh="coupler"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="right_spring_link" pos="0 0.0132 0.0609">
|
||
|
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658"
|
||
|
quat="0.663403 -0.244737 0.244737 0.663403"
|
||
|
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
|
||
|
<joint name="right_spring_link_joint" class="spring_link"/>
|
||
|
<geom class="2f85/visual" mesh="spring_link" material="2f85/black"/>
|
||
|
<geom class="2f85/collision" mesh="spring_link"/>
|
||
|
<body name="right_follower" pos="0 0.055 0.0375">
|
||
|
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
|
||
|
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
|
||
|
<joint name="right_follower_joint" class="follower"/>
|
||
|
<geom class="2f85/visual" mesh="follower" material="2f85/black"/>
|
||
|
<geom class="2f85/collision" mesh="follower"/>
|
||
|
<body name="right_pad" pos="0 -0.0189 0.01352">
|
||
|
<geom class="pad_box1" name="right_pad1"/>
|
||
|
<geom class="pad_box2" name="right_pad2"/>
|
||
|
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="0.707107 0 0 0.707107"
|
||
|
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
|
||
|
<geom class="2f85/visual" mesh="pad"/>
|
||
|
<body name="right_silicone_pad">
|
||
|
<geom class="2f85/visual" mesh="silicone_pad" material="2f85/black"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
<!-- Left-hand side 4-bar linkage -->
|
||
|
<body name="left_driver" pos="0 -0.0306011 0.054904" quat="0 0 0 1">
|
||
|
<inertial mass="0.00899563" pos="0 0.0177547 0.00107314" quat="0.681301 0.732003 0 0"
|
||
|
diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
|
||
|
<joint name="left_driver_joint" class="driver"/>
|
||
|
<geom class="2f85/visual" mesh="driver" material="2f85/gray"/>
|
||
|
<geom class="2f85/collision" mesh="driver"/>
|
||
|
<body name="left_coupler" pos="0 0.0315 -0.0041">
|
||
|
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175"
|
||
|
quat="0.705636 -0.0455904 0.0455904 0.705636"
|
||
|
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
|
||
|
<joint name="left_coupler_joint" class="coupler"/>
|
||
|
<geom class="2f85/visual" mesh="coupler" material="2f85/black"/>
|
||
|
<geom class="2f85/collision" mesh="coupler"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="left_spring_link" pos="0 -0.0132 0.0609" quat="0 0 0 1">
|
||
|
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658"
|
||
|
quat="0.663403 -0.244737 0.244737 0.663403"
|
||
|
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
|
||
|
<joint name="left_spring_link_joint" class="spring_link"/>
|
||
|
<geom class="2f85/visual" mesh="spring_link" material="2f85/black"/>
|
||
|
<geom class="2f85/collision" mesh="spring_link"/>
|
||
|
<body name="left_follower" pos="0 0.055 0.0375">
|
||
|
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
|
||
|
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
|
||
|
<joint name="left_follower_joint" class="follower"/>
|
||
|
<geom class="2f85/visual" mesh="follower" material="2f85/black"/>
|
||
|
<geom class="2f85/collision" mesh="follower"/>
|
||
|
<body name="left_pad" pos="0 -0.0189 0.01352">
|
||
|
<geom class="pad_box1" name="left_pad1"/>
|
||
|
<geom class="pad_box2" name="left_pad2"/>
|
||
|
<inertial mass="0.0035" pos="0 -0.0025 0.0185" quat="1 0 0 1"
|
||
|
diaginertia="4.73958e-07 3.64583e-07 1.23958e-07"/>
|
||
|
<geom class="2f85/visual" mesh="pad"/>
|
||
|
<body name="left_silicone_pad">
|
||
|
<geom class="2f85/visual" mesh="silicone_pad" material="2f85/black"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
<camera name="wrist" pos="0 -0.05639 -0.058475" quat="0 0 0 1" fovy="41.83792730009236"
|
||
|
resolution="640 480"/>
|
||
|
<site name="pinch_site" pos="0 0 -0.181525" quat="0 1 0 0"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</worldbody>
|
||
|
|
||
|
<contact>
|
||
|
<exclude body1="base" body2="left_driver"/>
|
||
|
<exclude body1="base" body2="right_driver"/>
|
||
|
<exclude body1="base" body2="left_spring_link"/>
|
||
|
<exclude body1="base" body2="right_spring_link"/>
|
||
|
<exclude body1="right_coupler" body2="right_follower"/>
|
||
|
<exclude body1="left_coupler" body2="left_follower"/>
|
||
|
</contact>
|
||
|
|
||
|
<tendon>
|
||
|
<fixed name="split">
|
||
|
<joint joint="right_driver_joint" coef="0.5"/>
|
||
|
<joint joint="left_driver_joint" coef="0.5"/>
|
||
|
</fixed>
|
||
|
</tendon>
|
||
|
|
||
|
<equality>
|
||
|
<connect anchor="0 0 0" body1="right_follower" body2="right_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
|
||
|
<connect anchor="0 0 0" body1="left_follower" body2="left_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
|
||
|
<joint joint1="right_driver_joint" joint2="left_driver_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001"
|
||
|
solref="0.005 1"/>
|
||
|
</equality>
|
||
|
|
||
|
<actuator>
|
||
|
<position name="joint_x" joint="joint_x" kp="1000000" kv="50000"/>
|
||
|
<position name="joint_y" joint="joint_y" kp="1000000" kv="50000"/>
|
||
|
<position name="joint_th" joint="joint_th" kp="50000" kv="1000"/>
|
||
|
<position class="large_actuator" name="joint_1" joint="joint_1"/>
|
||
|
<position class="large_actuator" name="joint_2" joint="joint_2" ctrlrange="-2.2497294058206907 2.2497294058206907"/>
|
||
|
<position class="large_actuator" name="joint_3" joint="joint_3"/>
|
||
|
<position class="large_actuator" name="joint_4" joint="joint_4" ctrlrange="-2.5795966344476193 2.5795966344476193"/>
|
||
|
<position class="small_actuator" name="joint_5" joint="joint_5"/>
|
||
|
<position class="small_actuator" name="joint_6" joint="joint_6" ctrlrange="-2.0996310901491784 2.0996310901491784"/>
|
||
|
<position class="small_actuator" name="joint_7" joint="joint_7"/>
|
||
|
<general class="2f85" name="fingers_actuator" tendon="split" forcerange="-5 5" ctrlrange="0 255"
|
||
|
gainprm="0.3137255 0 0" biasprm="0 -100 -10"/>
|
||
|
</actuator>
|
||
|
|
||
|
<keyframe>
|
||
|
<key name="home" qpos="0 0 0 0 0.26179939 3.14159265 -2.26892803 0 0.95993109 1.57079633 0 0 0 0 0 0 0 0"
|
||
|
ctrl="0 0 0 0 0.26179939 3.14159265 -2.26892803 0 0.95993109 1.57079633 0"/>
|
||
|
<key name="retract" qpos="0 0 0 0 -0.34906585 3.14159265 -2.54818071 0 -0.87266463 1.57079633 0 0 0 0 0 0 0 0"
|
||
|
ctrl="0 0 0 0 -0.34906585 3.14159265 -2.54818071 0 -0.87266463 1.57079633 0"/>
|
||
|
</keyframe>
|
||
|
</mujoco>
|