luckyworld/RobotData/kitchen/kitchenArm.xml
Goran Lazarevski 669cf5383b Lucky World source code
2025-03-18 19:25:25 +01:00

366 lines
18 KiB
XML

<mujoco model="panda">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<option integrator="implicitfast" impratio="10" cone="elliptic" noslip_iterations="3" timestep="0.0064">
<flag multiccd="enable" />
</option>
<default>
<default class="panda">
<material specular="0.5" shininess="0.25"/>
<joint armature="0.1" damping="1" axis="0 0 1" range="-2.8973 2.8973"/>
<general dyntype="none" biastype="affine" ctrlrange="-2.8973 2.8973" forcerange="-87 87"/>
<default class="finger">
<joint axis="0 1 0" type="slide" range="0 0.04"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom type="mesh" group="3"/>
<default class="fingertip_pad_collision_1">
<geom type="box" size="0.0085 0.004 0.0085" pos="0 0.0055 0.0445"/>
</default>
<default class="fingertip_pad_collision_2">
<geom type="box" size="0.003 0.002 0.003" pos="0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_3">
<geom type="box" size="0.003 0.002 0.003" pos="-0.0055 0.002 0.05"/>
</default>
<default class="fingertip_pad_collision_4">
<geom type="box" size="0.003 0.002 0.0035" pos="0.0055 0.002 0.0395"/>
</default>
<default class="fingertip_pad_collision_5">
<geom type="box" size="0.003 0.002 0.0035" pos="-0.0055 0.002 0.0395"/>
</default>
</default>
</default>
</default>
<asset>
<material class="panda" name="white" rgba="1 1 1 1"/>
<material class="panda" name="off_white" rgba="0.901961 0.921569 0.929412 1"/>
<material class="panda" name="black" rgba="0.25 0.25 0.25 1"/>
<material class="panda" name="green" rgba="0 1 0 1"/>
<material class="panda" name="light_blue" rgba="0.039216 0.541176 0.780392 1"/>
<!-- Collision meshes -->
<mesh name="link0_c" file="link0.stl"/>
<mesh name="link1_c" file="link1.stl"/>
<mesh name="link2_c" file="link2.stl"/>
<mesh name="link3_c" file="link3.stl"/>
<mesh name="link4_c" file="link4.stl"/>
<mesh name="link5_c0" file="link5_collision_0.obj"/>
<mesh name="link5_c1" file="link5_collision_1.obj"/>
<mesh name="link5_c2" file="link5_collision_2.obj"/>
<mesh name="link6_c" file="link6.stl"/>
<mesh name="link7_c" file="link7.stl"/>
<mesh name="hand_c" file="hand.stl"/>
<!-- Visual meshes -->
<mesh file="link0_0.obj"/>
<mesh file="link0_1.obj"/>
<mesh file="link0_2.obj"/>
<mesh file="link0_3.obj"/>
<mesh file="link0_4.obj"/>
<mesh file="link0_5.obj"/>
<mesh file="link0_7.obj"/>
<mesh file="link0_8.obj"/>
<mesh file="link0_9.obj"/>
<mesh file="link0_10.obj"/>
<mesh file="link0_11.obj"/>
<mesh file="link1.obj"/>
<mesh file="link2.obj"/>
<mesh file="link3_0.obj"/>
<mesh file="link3_1.obj"/>
<mesh file="link3_2.obj"/>
<mesh file="link3_3.obj"/>
<mesh file="link4_0.obj"/>
<mesh file="link4_1.obj"/>
<mesh file="link4_2.obj"/>
<mesh file="link4_3.obj"/>
<mesh file="link5_0.obj"/>
<mesh file="link5_1.obj"/>
<mesh file="link5_2.obj"/>
<mesh file="link6_0.obj"/>
<mesh file="link6_1.obj"/>
<mesh file="link6_2.obj"/>
<mesh file="link6_3.obj"/>
<mesh file="link6_4.obj"/>
<mesh file="link6_5.obj"/>
<mesh file="link6_6.obj"/>
<mesh file="link6_7.obj"/>
<mesh file="link6_8.obj"/>
<mesh file="link6_9.obj"/>
<mesh file="link6_10.obj"/>
<mesh file="link6_11.obj"/>
<mesh file="link6_12.obj"/>
<mesh file="link6_13.obj"/>
<mesh file="link6_14.obj"/>
<mesh file="link6_15.obj"/>
<mesh file="link6_16.obj"/>
<mesh file="link7_0.obj"/>
<mesh file="link7_1.obj"/>
<mesh file="link7_2.obj"/>
<mesh file="link7_3.obj"/>
<mesh file="link7_4.obj"/>
<mesh file="link7_5.obj"/>
<mesh file="link7_6.obj"/>
<mesh file="link7_7.obj"/>
<mesh file="hand_0.obj"/>
<mesh file="hand_1.obj"/>
<mesh file="hand_2.obj"/>
<mesh file="hand_3.obj"/>
<mesh file="hand_4.obj"/>
<mesh file="finger_0.obj"/>
<mesh file="finger_1.obj"/>
<mesh file="table1.obj"/>
<mesh file="table2.obj"/>
<mesh file="apple.obj"/>
<mesh file="can.obj"/>
<mesh file="carrot1.obj"/>
<mesh file="carrot2.obj"/>
<mesh file="corn.obj"/>
<mesh file="eggplant.obj"/>
<mesh file="plate.obj"/>
<mesh file="sink.obj"/>
<mesh file="sink1.obj"/>
<mesh file="sink2.obj"/>
<mesh file="sink3.obj"/>
<mesh file="sink4.obj"/>
<mesh file="sink5.obj"/>
<mesh file="sink6.obj"/>
<mesh file="sink7.obj"/>
<mesh file="sink8.obj"/>
<mesh file="sink9.obj"/>
</asset>
<worldbody>
<body name="Plane">
<geom type="plane" size="0 0 0.1" />
</body>
<!--Tables -->
<geom type="mesh" mesh="table1" pos="0 0 0" friction="1.2 0.8 0.3" density="1500" />
<geom type="mesh" material="white" mesh="table2" pos="0 0 0" friction="1.2 0.8 0.3" density="1500" />
<body name="sink" pos="0 0 0" >
<geom type="mesh" mesh="sink" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink1" pos="0 0 0" >
<geom type="mesh" mesh="sink1" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink2" pos="0 0 0" >
<geom type="mesh" mesh="sink2" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink3" pos="0 0 0" >
<geom type="mesh" mesh="sink3" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink4" pos="0 0 0" >
<geom type="mesh" mesh="sink4" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink5" pos="0 0 0" >
<geom type="mesh" mesh="sink5" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink6" pos="0 0 0" >
<geom type="mesh" mesh="sink6" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink7" pos="0 0 0" >
<geom type="mesh" mesh="sink7" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink8" pos="0 0 0" >
<geom type="mesh" mesh="sink8" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<body name="sink9" pos="0 0 0" >
<geom type="mesh" mesh="sink9" pos="0 0 0" group="2" friction="0.3 0.05 0.02" density="7850" />
</body>
<!--dynamics -->
<body name="apple" pos="0.861 1.411 0.599" >
<geom type="mesh" mass="0.045" material="black" friction="0.4 0.3 0.1" density="700" mesh="apple" />
<freejoint />
</body>
<body name="can" pos="0.862 1.303 0.533">
<geom type="mesh" mass="0.002" mesh="can" pos="0 0 0" group="2" density="7850" friction="0.3 0.05 0.02"/>
<freejoint />
</body>
<body name="carrot1" pos="0.712 1.262 0.586">
<geom type="mesh" mass="0.0022" mesh="carrot1" pos="0 0 0" group="2" density="1500" friction="1.2 0.8 0.3"/>
<freejoint />
</body>
<body name="carrot2" pos="0.781 1.262 0.586" >
<geom type="mesh" mass="0.0022" mesh="carrot2" pos="0 0 0" group="2" density="1500" friction="1.2 0.8 0.3"/>
<joint type="free"/>
</body>
<body name="corn" pos="0.862 0.964 0.586">
<geom type="mesh" mass="0.0031" mesh="corn" pos="0 0 0" group="2" density="1500" friction="1.2 0.8 0.3"/>
<freejoint />
</body>
<body name="eggplant" pos="0.607 1.609 0.585">
<geom type="mesh" mass="0.0029" mesh="eggplant" pos="0 0 0" group="2" density="1500" friction="1.2 0.8 0.3"/>
<freejoint />
</body>
<body name="plate" pos="0.695 1.007 0.579">
<geom type="mesh" mass="0.0021" mesh="plate" pos="0 0 0" group="2" density="1200" friction="0.4 0.3 0.1"/>
<freejoint />
</body>
<body name="link0" childclass="panda" pos="0.35 1.5 0.2">
<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="visual"/>
<geom mesh="link0_1" material="black" class="visual"/>
<geom mesh="link0_2" material="off_white" class="visual"/>
<geom mesh="link0_3" material="black" class="visual"/>
<geom mesh="link0_4" material="off_white" class="visual"/>
<geom mesh="link0_5" material="black" class="visual"/>
<geom mesh="link0_7" material="white" class="visual"/>
<geom mesh="link0_8" material="white" class="visual"/>
<geom mesh="link0_9" material="black" class="visual"/>
<geom mesh="link0_10" material="off_white" class="visual"/>
<geom mesh="link0_11" material="white" class="visual"/>
<geom mesh="link0_c" class="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"/>
<geom material="white" mesh="link1" class="visual"/>
<geom mesh="link1_c" class="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"/>
<geom material="white" mesh="link2" class="visual"/>
<geom mesh="link2_c" class="collision"/>
<body name="link3" pos="0 -0.316 0" quat="1 1 0 0">
<joint name="joint3"/>
<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"/>
<geom mesh="link3_0" material="white" class="visual"/>
<geom mesh="link3_1" material="white" class="visual"/>
<geom mesh="link3_2" material="white" class="visual"/>
<geom mesh="link3_3" material="black" class="visual"/>
<geom mesh="link3_c" class="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"/>
<geom mesh="link4_0" material="white" class="visual"/>
<geom mesh="link4_1" material="white" class="visual"/>
<geom mesh="link4_2" material="black" class="visual"/>
<geom mesh="link4_3" material="white" class="visual"/>
<geom mesh="link4_c" class="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"/>
<geom mesh="link5_0" material="black" class="visual"/>
<geom mesh="link5_1" material="white" class="visual"/>
<geom mesh="link5_2" material="white" class="visual"/>
<geom mesh="link5_c0" class="collision"/>
<geom mesh="link5_c1" class="collision"/>
<geom mesh="link5_c2" class="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"/>
<geom mesh="link6_0" material="off_white" class="visual"/>
<geom mesh="link6_1" material="white" class="visual"/>
<geom mesh="link6_2" material="black" class="visual"/>
<geom mesh="link6_3" material="white" class="visual"/>
<geom mesh="link6_4" material="white" class="visual"/>
<geom mesh="link6_5" material="white" class="visual"/>
<geom mesh="link6_6" material="white" class="visual"/>
<geom mesh="link6_7" material="light_blue" class="visual"/>
<geom mesh="link6_8" material="light_blue" class="visual"/>
<geom mesh="link6_9" material="black" class="visual"/>
<geom mesh="link6_10" material="black" class="visual"/>
<geom mesh="link6_11" material="white" class="visual"/>
<geom mesh="link6_12" material="green" class="visual"/>
<geom mesh="link6_13" material="white" class="visual"/>
<geom mesh="link6_14" material="black" class="visual"/>
<geom mesh="link6_15" material="black" class="visual"/>
<geom mesh="link6_16" material="white" class="visual"/>
<geom mesh="link6_c" class="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"/>
<geom mesh="link7_0" material="white" class="visual"/>
<geom mesh="link7_1" material="black" class="visual"/>
<geom mesh="link7_2" material="black" class="visual"/>
<geom mesh="link7_3" material="black" class="visual"/>
<geom mesh="link7_4" material="black" class="visual"/>
<geom mesh="link7_5" material="black" class="visual"/>
<geom mesh="link7_6" material="black" class="visual"/>
<geom mesh="link7_7" material="white" class="visual"/>
<geom mesh="link7_c" class="collision"/>
<body name="hand" pos="0 0 0.107" quat="0.9238795 0 0 -0.3826834">
<inertial mass="0.73" pos="-0.01 0 0.03" diaginertia="0.001 0.0025 0.0017"/>
<geom mesh="hand_0" material="off_white" class="visual"/>
<geom mesh="hand_1" material="black" class="visual"/>
<geom mesh="hand_2" material="black" class="visual"/>
<geom mesh="hand_3" material="white" class="visual"/>
<geom mesh="hand_4" material="off_white" class="visual"/>
<geom mesh="hand_c" class="collision"/>
<body name="left_finger" pos="0 0 0.0584">
<inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
<joint name="finger_joint1" class="finger"/>
<geom mesh="finger_0" material="off_white" class="visual"/>
<geom mesh="finger_1" material="black" class="visual" friction="10 0.8 0.3"/>
<geom mesh="finger_0" class="collision"/>
<geom class="fingertip_pad_collision_1"/>
<geom class="fingertip_pad_collision_2"/>
<geom class="fingertip_pad_collision_3"/>
<geom class="fingertip_pad_collision_4"/>
<geom class="fingertip_pad_collision_5"/>
</body>
<body name="right_finger" pos="0 0 0.0584" quat="0 0 0 1">
<inertial mass="0.015" pos="0 0 0" diaginertia="2.375e-6 2.375e-6 7.5e-7"/>
<joint name="finger_joint2" class="finger"/>
<geom mesh="finger_0" material="off_white" class="visual"friction="1.2 0.8 0.3"/>
<geom mesh="finger_1" material="black" class="visual"friction="10 0.8 0.3"/>
<geom mesh="finger_0" class="collision"friction="1.2 0.8 0.3"/>
<geom class="fingertip_pad_collision_1"friction="1.2 0.8 0.3"/>
<geom class="fingertip_pad_collision_2"friction="1.2 0.8 0.3"/>
<geom class="fingertip_pad_collision_3"friction="1.2 0.8 0.3"/>
<geom class="fingertip_pad_collision_4"friction="1.2 0.8 0.3"/>
<geom class="fingertip_pad_collision_5"friction="1.2 0.8 0.3"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<tendon>
<fixed name="split">
<joint joint="finger_joint1" coef="0.5"/>
<joint joint="finger_joint2" coef="0.5"/>
</fixed>
</tendon>
<equality>
<joint joint1="finger_joint1" joint2="finger_joint2" solimp="0.95 0.99 0.001" solref="0.005 1"/>
</equality>
<actuator>
<general class="panda" name="bodyRot" joint="joint1" gainprm="4500" biasprm="0 -4500 -450"/>
<general class="panda" name="shoulder" joint="joint2" gainprm="4500" biasprm="0 -4500 -450"
ctrlrange="-1.7628 1.7628"/>
<general class="panda" name="shoulderRot" joint="joint3" gainprm="3500" biasprm="0 -3500 -350"/>
<general class="panda" name="elbow" joint="joint4" gainprm="3500" biasprm="0 -3500 -350"
ctrlrange="-3.0718 -0.0698"/>
<general class="panda" name="elbowRot" joint="joint5" gainprm="2000" biasprm="0 -2000 -200" forcerange="-12 12"/>
<general class="panda" name="hand" joint="joint6" gainprm="2000" biasprm="0 -2000 -200" forcerange="-12 12"
ctrlrange="-0.0175 3.7525"/>
<general class="panda" name="handRot" joint="joint7" gainprm="2000" biasprm="0 -2000 -200" forcerange="-12 12"/>
<!-- Remap original ctrlrange (0, 0.04) to (0, 255): 0.04 * 100 / 255 = 0.01568627451 -->
<general class="panda" name="gripper" tendon="split" forcerange="-100 100" ctrlrange="0 255"
gainprm="0.01568627451 0 0" biasprm="0 -100 -10"/>
</actuator>
</mujoco>