gym_hil/assets/panda.xml (387 lines of code) (raw):
<mujoco model="panda">
<compiler angle="radian" autolimits="true"/>
<default>
<default class="panda">
<joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/>
<default class="panda/visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="panda/collision">
<geom type="mesh" group="3"/>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
<default class="2f85">
<mesh scale="0.001 0.001 0.001"/>
<general biastype="affine"/>
<site type="sphere" rgba="0.9 0.9 0.9 1" size="0.005" group="4"/>
<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" 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" stiffness="0.05" springref="2.62" damping="0.00125"/>
</default>
<default class="coupler">
<joint range="-1.57 0" 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>
</default>
<asset>
<material name="white" rgba="1 1 1 1"/>
<material name="off_white" rgba="0.901961 0.921569 0.929412 1"/>
<material name="dark_grey" rgba="0.25 0.25 0.25 1"/>
<material name="green" rgba="0 1 0 1"/>
<material name="light_blue" rgba="0.039216 0.541176 0.780392 1"/>
<material name="metal" rgba="0.58 0.58 0.58 1"/>
<material name="silicone" rgba="0.1882 0.1882 0.1882 1"/>
<material name="gray" rgba="0.4627 0.4627 0.4627 1"/>
<material name="black" rgba="0.149 0.149 0.149 1"/>
<mesh name="link0_c" file="franka_emika_panda/meshes/link0.stl"/>
<mesh name="link1_c" file="franka_emika_panda/meshes/link1.stl"/>
<mesh name="link2_c" file="franka_emika_panda/meshes/link2.stl"/>
<mesh name="link3_c" file="franka_emika_panda/meshes/link3.stl"/>
<mesh name="link4_c" file="franka_emika_panda/meshes/link4.stl"/>
<mesh name="link5_c0" file="franka_emika_panda/meshes/link5_collision_0.obj"/>
<mesh name="link5_c1" file="franka_emika_panda/meshes/link5_collision_1.obj"/>
<mesh name="link5_c2" file="franka_emika_panda/meshes/link5_collision_2.obj"/>
<mesh name="link6_c" file="franka_emika_panda/meshes/link6.stl"/>
<mesh name="link7_c" file="franka_emika_panda/meshes/link7.stl"/>
<mesh file="franka_emika_panda/meshes/link0_0.obj"/>
<mesh file="franka_emika_panda/meshes/link0_1.obj"/>
<mesh file="franka_emika_panda/meshes/link0_2.obj"/>
<mesh file="franka_emika_panda/meshes/link0_3.obj"/>
<mesh file="franka_emika_panda/meshes/link0_4.obj"/>
<mesh file="franka_emika_panda/meshes/link0_5.obj"/>
<mesh file="franka_emika_panda/meshes/link0_7.obj"/>
<mesh file="franka_emika_panda/meshes/link0_8.obj"/>
<mesh file="franka_emika_panda/meshes/link0_9.obj"/>
<mesh file="franka_emika_panda/meshes/link0_10.obj"/>
<mesh file="franka_emika_panda/meshes/link0_11.obj"/>
<mesh file="franka_emika_panda/meshes/link1.obj"/>
<mesh file="franka_emika_panda/meshes/link2.obj"/>
<mesh file="franka_emika_panda/meshes/link3_0.obj"/>
<mesh file="franka_emika_panda/meshes/link3_1.obj"/>
<mesh file="franka_emika_panda/meshes/link3_2.obj"/>
<mesh file="franka_emika_panda/meshes/link3_3.obj"/>
<mesh file="franka_emika_panda/meshes/link4_0.obj"/>
<mesh file="franka_emika_panda/meshes/link4_1.obj"/>
<mesh file="franka_emika_panda/meshes/link4_2.obj"/>
<mesh file="franka_emika_panda/meshes/link4_3.obj"/>
<mesh file="franka_emika_panda/meshes/link5_0.obj"/>
<mesh file="franka_emika_panda/meshes/link5_1.obj"/>
<mesh file="franka_emika_panda/meshes/link5_2.obj"/>
<mesh file="franka_emika_panda/meshes/link6_0.obj"/>
<mesh file="franka_emika_panda/meshes/link6_1.obj"/>
<mesh file="franka_emika_panda/meshes/link6_2.obj"/>
<mesh file="franka_emika_panda/meshes/link6_3.obj"/>
<mesh file="franka_emika_panda/meshes/link6_4.obj"/>
<mesh file="franka_emika_panda/meshes/link6_5.obj"/>
<mesh file="franka_emika_panda/meshes/link6_6.obj"/>
<mesh file="franka_emika_panda/meshes/link6_7.obj"/>
<mesh file="franka_emika_panda/meshes/link6_8.obj"/>
<mesh file="franka_emika_panda/meshes/link6_9.obj"/>
<mesh file="franka_emika_panda/meshes/link6_10.obj"/>
<mesh file="franka_emika_panda/meshes/link6_11.obj"/>
<mesh file="franka_emika_panda/meshes/link6_12.obj"/>
<mesh file="franka_emika_panda/meshes/link6_13.obj"/>
<mesh file="franka_emika_panda/meshes/link6_14.obj"/>
<mesh file="franka_emika_panda/meshes/link6_15.obj"/>
<mesh file="franka_emika_panda/meshes/link6_16.obj"/>
<mesh file="franka_emika_panda/meshes/link7_0.obj"/>
<mesh file="franka_emika_panda/meshes/link7_1.obj"/>
<mesh file="franka_emika_panda/meshes/link7_2.obj"/>
<mesh file="franka_emika_panda/meshes/link7_3.obj"/>
<mesh file="franka_emika_panda/meshes/link7_4.obj"/>
<mesh file="franka_emika_panda/meshes/link7_5.obj"/>
<mesh file="franka_emika_panda/meshes/link7_6.obj"/>
<mesh file="franka_emika_panda/meshes/link7_7.obj"/>
<mesh class="2f85" file="robotiq_2f85/meshes/base_mount.stl"/>
<mesh class="2f85" file="robotiq_2f85/meshes/base.stl"/>
<mesh class="2f85" file="robotiq_2f85/meshes/driver.stl"/>
<mesh class="2f85" file="robotiq_2f85/meshes/coupler.stl"/>
<mesh class="2f85" file="robotiq_2f85/meshes/follower.stl"/>
<mesh class="2f85" file="robotiq_2f85/meshes/pad.stl"/>
<mesh class="2f85" file="robotiq_2f85/meshes/silicone_pad.stl"/>
<mesh class="2f85" file="robotiq_2f85/meshes/spring_link.stl"/>
</asset>
<worldbody>
<body name="link0" childclass="panda">
<inertial mass="0.629769" pos="-0.041018 -0.00014 0.049974"
fullinertia="0.00315 0.00388 0.004285 8.2904e-7 0.00015 8.2299e-6"/>
<geom mesh="link0_0" material="off_white" class="panda/visual"/>
<geom mesh="link0_1" material="dark_grey" class="panda/visual"/>
<geom mesh="link0_2" material="off_white" class="panda/visual"/>
<geom mesh="link0_3" material="dark_grey" class="panda/visual"/>
<geom mesh="link0_4" material="off_white" class="panda/visual"/>
<geom mesh="link0_5" material="dark_grey" class="panda/visual"/>
<geom mesh="link0_7" material="white" class="panda/visual"/>
<geom mesh="link0_8" material="white" class="panda/visual"/>
<geom mesh="link0_9" material="dark_grey" class="panda/visual"/>
<geom mesh="link0_10" material="off_white" class="panda/visual"/>
<geom mesh="link0_11" material="white" class="panda/visual"/>
<geom mesh="link0_c" class="panda/collision"/>
<body name="link1" pos="0 0 0.333">
<inertial mass="4.970684" pos="0.003875 0.002081 -0.04762"
fullinertia="0.70337 0.70661 0.0091170 -0.00013900 0.0067720 0.019169"/>
<joint name="joint1"/>
<site name="joint1"/>
<geom material="white" mesh="link1" class="panda/visual"/>
<geom mesh="link1_c" class="panda/collision"/>
<body name="link2" quat="1 -1 0 0">
<inertial mass="0.646926" pos="-0.003141 -0.02872 0.003495"
fullinertia="0.0079620 2.8110e-2 2.5995e-2 -3.925e-3 1.0254e-2 7.04e-4"/>
<joint name="joint2" range="-1.7628 1.7628"/>
<site name="joint2"/>
<geom material="white" mesh="link2" class="panda/visual"/>
<geom mesh="link2_c" class="panda/collision"/>
<body name="link3" pos="0 -0.316 0" quat="1 1 0 0">
<inertial mass="3.228604" pos="2.7518e-2 3.9252e-2 -6.6502e-2"
fullinertia="3.7242e-2 3.6155e-2 1.083e-2 -4.761e-3 -1.1396e-2 -1.2805e-2"/>
<joint name="joint3"/>
<site name="joint3"/>
<geom mesh="link3_0" material="white" class="panda/visual"/>
<geom mesh="link3_1" material="white" class="panda/visual"/>
<geom mesh="link3_2" material="white" class="panda/visual"/>
<geom mesh="link3_3" material="dark_grey" class="panda/visual"/>
<geom mesh="link3_c" class="panda/collision"/>
<body name="link4" pos="0.0825 0 0" quat="1 1 0 0">
<inertial mass="3.587895" pos="-5.317e-2 1.04419e-1 2.7454e-2"
fullinertia="2.5853e-2 1.9552e-2 2.8323e-2 7.796e-3 -1.332e-3 8.641e-3"/>
<joint name="joint4" range="-3.0718 -0.0698"/>
<site name="joint4"/>
<geom mesh="link4_0" material="white" class="panda/visual"/>
<geom mesh="link4_1" material="white" class="panda/visual"/>
<geom mesh="link4_2" material="dark_grey" class="panda/visual"/>
<geom mesh="link4_3" material="white" class="panda/visual"/>
<geom mesh="link4_c" class="panda/collision"/>
<body name="link5" pos="-0.0825 0.384 0" quat="1 -1 0 0">
<inertial mass="1.225946" pos="-1.1953e-2 4.1065e-2 -3.8437e-2"
fullinertia="3.5549e-2 2.9474e-2 8.627e-3 -2.117e-3 -4.037e-3 2.29e-4"/>
<joint name="joint5"/>
<site name="joint5"/>
<geom mesh="link5_0" material="dark_grey" class="panda/visual"/>
<geom mesh="link5_1" material="white" class="panda/visual"/>
<geom mesh="link5_2" material="white" class="panda/visual"/>
<geom mesh="link5_c0" class="panda/collision"/>
<geom mesh="link5_c1" class="panda/collision"/>
<geom mesh="link5_c2" class="panda/collision"/>
<body name="link6" quat="1 1 0 0">
<inertial mass="1.666555" pos="6.0149e-2 -1.4117e-2 -1.0517e-2"
fullinertia="1.964e-3 4.354e-3 5.433e-3 1.09e-4 -1.158e-3 3.41e-4"/>
<joint name="joint6" range="-0.0175 3.7525"/>
<site name="joint6"/>
<geom mesh="link6_0" material="off_white" class="panda/visual"/>
<geom mesh="link6_1" material="white" class="panda/visual"/>
<geom mesh="link6_2" material="dark_grey" class="panda/visual"/>
<geom mesh="link6_3" material="white" class="panda/visual"/>
<geom mesh="link6_4" material="white" class="panda/visual"/>
<geom mesh="link6_5" material="white" class="panda/visual"/>
<geom mesh="link6_6" material="white" class="panda/visual"/>
<geom mesh="link6_7" material="light_blue" class="panda/visual"/>
<geom mesh="link6_8" material="light_blue" class="panda/visual"/>
<geom mesh="link6_9" material="dark_grey" class="panda/visual"/>
<geom mesh="link6_10" material="dark_grey" class="panda/visual"/>
<geom mesh="link6_11" material="white" class="panda/visual"/>
<geom mesh="link6_12" material="green" class="panda/visual"/>
<geom mesh="link6_13" material="white" class="panda/visual"/>
<geom mesh="link6_14" material="dark_grey" class="panda/visual"/>
<geom mesh="link6_15" material="dark_grey" class="panda/visual"/>
<geom mesh="link6_16" material="white" class="panda/visual"/>
<geom mesh="link6_c" class="panda/collision"/>
<body name="link7" pos="0.088 0 0" quat="1 1 0 0">
<inertial mass="7.35522e-01" pos="1.0517e-2 -4.252e-3 6.1597e-2"
fullinertia="1.2516e-2 1.0027e-2 4.815e-3 -4.28e-4 -1.196e-3 -7.41e-4"/>
<joint name="joint7"/>
<site name="joint7"/>
<geom mesh="link7_0" material="white" class="panda/visual"/>
<geom mesh="link7_1" material="dark_grey" class="panda/visual"/>
<geom mesh="link7_2" material="dark_grey" class="panda/visual"/>
<geom mesh="link7_3" material="dark_grey" class="panda/visual"/>
<geom mesh="link7_4" material="dark_grey" class="panda/visual"/>
<geom mesh="link7_5" material="dark_grey" class="panda/visual"/>
<geom mesh="link7_6" material="dark_grey" class="panda/visual"/>
<geom mesh="link7_7" material="white" class="panda/visual"/>
<geom mesh="link7_c" class="panda/collision"/>
<body name="attachment" pos="0 0 0.107" quat="0.3826834 0 0 0.9238795">
<camera name="handcam_depth" pos="-0.05 0 0" fovy="62" quat="0 1 -1 0"/>
<camera name="handcam_rgb" pos="-0.05 0.015 0" fovy="42.5" quat="0 1 -1 0"/>
<site name="attachment_site" quat="0 0 0 1"/>
<body name="base_mount" quat="-1 0 0 1" childclass="2f85">
<geom class="2f85/visual" mesh="base_mount" material="black"/>
<geom class="2f85/collision" mesh="base_mount"/>
<body name="base" pos="0 0 0.0038" quat="1 0 0 -1">
<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="black"/>
<geom class="2f85/collision" mesh="base"/>
<site name="pinch" pos="0 0 0.145"/>
<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="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="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="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="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="black"/>
</body>
</body>
</body>
</body>
<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="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="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="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="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="black"/>
</body>
</body>
</body>
</body>
</body>
</body>
</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>
<motor class="panda" name="actuator1" joint="joint1" ctrlrange="-87 87"/>
<motor class="panda" name="actuator2" joint="joint2" ctrlrange="-87 87"/>
<motor class="panda" name="actuator3" joint="joint3" ctrlrange="-87 87"/>
<motor class="panda" name="actuator4" joint="joint4" ctrlrange="-87 87"/>
<motor class="panda" name="actuator5" joint="joint5" ctrlrange="-12 12"/>
<motor class="panda" name="actuator6" joint="joint6" ctrlrange="-12 12"/>
<motor class="panda" name="actuator7" joint="joint7" ctrlrange="-12 12"/>
<general class="2f85" name="fingers_actuator" tendon="split" forcerange="-5 5" ctrlrange="0 255"
gainprm="0.3137255 0 0" biasprm="0 -100 -10"/>
</actuator>
<sensor>
<jointpos name="panda/joint1_pos" joint="joint1"/>
<jointpos name="panda/joint2_pos" joint="joint2"/>
<jointpos name="panda/joint3_pos" joint="joint3"/>
<jointpos name="panda/joint4_pos" joint="joint4"/>
<jointpos name="panda/joint5_pos" joint="joint5"/>
<jointpos name="panda/joint6_pos" joint="joint6"/>
<jointpos name="panda/joint7_pos" joint="joint7"/>
<jointvel name="panda/joint1_vel" joint="joint1"/>
<jointvel name="panda/joint2_vel" joint="joint2"/>
<jointvel name="panda/joint3_vel" joint="joint3"/>
<jointvel name="panda/joint4_vel" joint="joint4"/>
<jointvel name="panda/joint5_vel" joint="joint5"/>
<jointvel name="panda/joint6_vel" joint="joint6"/>
<jointvel name="panda/joint7_vel" joint="joint7"/>
<torque name="panda/joint1_torque" site="joint1"/>
<torque name="panda/joint2_torque" site="joint2"/>
<torque name="panda/joint3_torque" site="joint3"/>
<torque name="panda/joint4_torque" site="joint4"/>
<torque name="panda/joint5_torque" site="joint5"/>
<torque name="panda/joint6_torque" site="joint6"/>
<torque name="panda/joint7_torque" site="joint7"/>
<force name="panda/wrist_force" site="attachment_site"/>
<framepos name="2f85/pinch_pos" objtype="site" objname="pinch"/>
<framequat name="2f85/pinch_quat" objtype="site" objname="pinch"/>
<framelinvel name="2f85/pinch_vel" objtype="site" objname="pinch"/>
<frameangvel name="2f85/pinch_angvel" objtype="site" objname="pinch"/>
</sensor>
</mujoco>