| <mujoco model="mano"> |
| <compiler angle="radian" meshdir="meshes/" /> |
|
|
| <default> |
| |
| <geom density="800" condim="1" contype="0" conaffinity="0" /> |
| |
| <position kp="300" dampratio="1.0" inheritrange="0" /> |
| <joint damping="0.0" armature="1.0" frictionloss="0.0" /> |
| <site size="0.01" type="sphere" rgba="1 0 0 1" group="3" /> |
|
|
| <default class="left_base_slide"> |
| <joint type="slide" axis="0 1 0" range="-3.0 3.0" /> |
| <position kp="1000" ctrlrange="-3.0 3.0" /> |
| </default> |
| <default class="left_base_hinge"> |
| <joint axis="0 0 1" range="-6.28 6.28" /> |
| <position kp="1000" ctrlrange="-6.28 6.28" /> |
| </default> |
| </default> |
|
|
| <asset> |
| <texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" |
| height="3072" /> |
| <texture type="2d" name="left_groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" |
| rgb2="0.1 0.2 0.3" |
| markrgb="0.8 0.8 0.8" width="300" height="300" /> |
| <material name="left_groundplane" texture="left_groundplane" texuniform="true" |
| texrepeat="5 5" |
| reflectance="0.2" /> |
| <mesh name="left_palm_vis" content_type="model/obj" file="left_meshes/palm_vis.obj" /> |
| <mesh name="left_palm_collision" content_type="model/obj" file="left_meshes/palm_collision.obj" /> |
| <mesh name="left_index1_vis" content_type="model/obj" file="left_meshes/index1_vis.obj" /> |
| <mesh name="left_index1_collision" content_type="model/obj" |
| file="left_meshes/index1_collision.obj" /> |
| <mesh name="left_index2_vis" content_type="model/obj" file="left_meshes/index2_vis.obj" /> |
| <mesh name="left_index2_collision" content_type="model/obj" |
| file="left_meshes/index2_collision.obj" /> |
| <mesh name="left_index3_vis" content_type="model/obj" file="left_meshes/index3_vis.obj" /> |
| <mesh name="left_index3_collision" content_type="model/obj" |
| file="left_meshes/index3_collision.obj" /> |
| <mesh name="left_middle1_vis" content_type="model/obj" file="left_meshes/middle1_vis.obj" /> |
| <mesh name="left_middle1_collision" content_type="model/obj" |
| file="left_meshes/middle1_collision.obj" /> |
| <mesh name="left_middle2_vis" content_type="model/obj" file="left_meshes/middle2_vis.obj" /> |
| <mesh name="left_middle2_collision" content_type="model/obj" |
| file="left_meshes/middle2_collision.obj" /> |
| <mesh name="left_middle3_vis" content_type="model/obj" file="left_meshes/middle3_vis.obj" /> |
| <mesh name="left_middle3_collision" content_type="model/obj" |
| file="left_meshes/middle3_collision.obj" /> |
| <mesh name="left_pinky1_vis" content_type="model/obj" file="left_meshes/pinky1_vis.obj" /> |
| <mesh name="left_pinky1_collision" content_type="model/obj" |
| file="left_meshes/pinky1_collision.obj" /> |
| <mesh name="left_pinky2_vis" content_type="model/obj" file="left_meshes/pinky2_vis.obj" /> |
| <mesh name="left_pinky2_collision" content_type="model/obj" |
| file="left_meshes/pinky2_collision.obj" /> |
| <mesh name="left_pinky3_vis" content_type="model/obj" file="left_meshes/pinky3_vis.obj" /> |
| <mesh name="left_pinky3_collision" content_type="model/obj" |
| file="left_meshes/pinky3_collision.obj" /> |
| <mesh name="left_ring1_vis" content_type="model/obj" file="left_meshes/ring1_vis.obj" /> |
| <mesh name="left_ring1_collision" content_type="model/obj" |
| file="left_meshes/ring1_collision.obj" /> |
| <mesh name="left_ring2_vis" content_type="model/obj" file="left_meshes/ring2_vis.obj" /> |
| <mesh name="left_ring2_collision" content_type="model/obj" |
| file="left_meshes/ring2_collision.obj" /> |
| <mesh name="left_ring3_vis" content_type="model/obj" file="left_meshes/ring3_vis.obj" /> |
| <mesh name="left_ring3_collision" content_type="model/obj" |
| file="left_meshes/ring3_collision.obj" /> |
| <mesh name="left_thumb1_vis" content_type="model/obj" file="left_meshes/thumb1_vis.obj" /> |
| <mesh name="left_thumb1_collision" content_type="model/obj" |
| file="left_meshes/thumb1_collision.obj" /> |
| <mesh name="left_thumb2_vis" content_type="model/obj" file="left_meshes/thumb2_vis.obj" /> |
| <mesh name="left_thumb2_collision" content_type="model/obj" |
| file="left_meshes/thumb2_collision.obj" /> |
| <mesh name="left_thumb3_vis" content_type="model/obj" file="left_meshes/thumb3_vis.obj" /> |
| <mesh name="left_thumb3_collision" content_type="model/obj" |
| file="left_meshes/thumb3_collision.obj" /> |
| </asset> |
|
|
|
|
| <worldbody> |
| <body name="left_palm" gravcomp="1"> |
| <joint name="left_pos_x" axis="1 0 0" class="left_base_slide" /> |
| <joint name="left_pos_y" axis="0 1 0" class="left_base_slide" /> |
| <joint name="left_pos_z" axis="0 0 1" class="left_base_slide" /> |
| <joint name="left_rot_x" axis="1 0 0" class="left_base_hinge" /> |
| <joint name="left_rot_y" axis="0 1 0" class="left_base_hinge" /> |
| <joint name="left_rot_z" axis="0 0 1" class="left_base_hinge" /> |
|
|
| <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="left_palm_vis" /> |
| <geom name="collision_hand_left_palm_0" type="box" size="0.04 0.02 0.01" pos="0.04 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <site name="left_palm" pos="0.0946604 -0.00147896 -0.00335754" quat="1 -1 1 -1" /> |
|
|
| <body name="left_index1y" pos="0.0880972 -0.00520036 0.020686" |
| quat="0.992949 0.00330198 -0.115013 -0.0285073"> |
| <camera name="left_track" pos="0.868 -0.348 -0.175" |
| xyaxes="0.037 0.999 -0.000 0.011 -0.000 1.000" /> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_index1y" pos="0 0 0" axis="0 -1 0" range="-0.174533 0.174533" /> |
| <body name="left_index1z"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_index1z" pos="0 0 0" axis="0 0 -1" range="0 1.5708" /> |
| <geom quat="0.992949 -0.00330198 0.115013 0.0285073" type="mesh" contype="0" |
| conaffinity="0" |
| group="1" density="0" mesh="left_index1_vis" /> |
| <geom name="collision_hand_left_index_1" type="capsule" size="0.008 0.016" pos="0.016 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_index2" pos="0.0320372 0.00585704 -0.00531176" |
| quat="0.992687 0.00261912 0.0813131 0.0891864"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_index2" pos="0 0 0" axis="0 0 -1" range="0 1.74533" /> |
| <geom quat="0.997574 0.00206105 0.0338008 -0.0608285" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_index2_vis" /> |
| <geom name="collision_hand_left_index_2" type="capsule" size="0.007 0.011" |
| pos="0.011 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_index3" pos="0.0217759 -0.00397366 -0.00161355" |
| quat="0.995276 0.00115242 0.0364189 -0.0899872"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_index3" pos="0 0 0" axis="0 0 -1" range="0 1.39626" /> |
| <geom quat="0.999568 7.53592e-05 -0.00257406 0.0292638" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_index3_vis" /> |
| <geom name="collision_hand_left_index_3" type="capsule" size="0.006 0.009" |
| pos="0.009 0 0" group="3" rgba="0 1 0 1" /> |
| <site name="trace_hand_left_index_tip" pos="0.023106 -0.003671 0" size="0.005" |
| rgba="1 0 0 1" /> |
| <site name="track_hand_left_index_tip" pos="0.023106 -0.003671 0" size="0.005" |
| rgba="0 0 1 1" /> |
| <site name="left_index_tip" pos="0.023106 -0.003671 0" quat="1 0 0 0" /> |
| </body> |
| </body> |
| </body> |
| </body> |
|
|
| <body name="left_middle1y" pos="0.0946604 -0.00147896 -0.00335754" |
| quat="0.999812 -0.000138377 0.0177257 -0.0078051"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_middle1y" pos="0 0 0" axis="0 -1 0" range="-0.174533 0.174533" /> |
| <body name="left_middle1z"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_middle1z" pos="0 0 0" axis="0 0 -1" range="0 1.5708" /> |
| <geom quat="0.999812 0.000138377 -0.0177257 0.0078051" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_middle1_vis" /> |
| <geom name="collision_hand_left_middle_1" type="capsule" size="0.008 0.016" |
| pos="0.016 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_middle2" pos="0.0313285 0.00235072 -0.00448566" |
| quat="0.99679 0.00152841 0.0709577 0.037047"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_middle2" pos="0 0 0" axis="0 0 -1" range="0 1.74533" /> |
| <geom quat="0.995635 -0.00260071 -0.0886064 -0.0292231" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_middle2_vis" /> |
| <geom name="collision_hand_left_middle_2" type="capsule" size="0.007 0.012" |
| pos="0.012 0 0" group="3" rgba="0 1 0 1" /> |
| <body name="left_middle3" pos="0.0231278 -0.00261309 0.00016224" |
| quat="0.998412 -8.48904e-06 -0.00349023 -0.0562232"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_middle3" pos="0 0 0" axis="0 0 -1" range="0 1.39626" /> |
| <geom quat="0.996006 0.00229162 -0.0851367 0.0268094" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_middle3_vis" /> |
| <geom name="collision_hand_left_middle_3" type="capsule" size="0.006 0.010" |
| pos="0.010 0 0" group="3" rgba="0 1 0 1" /> |
| <site name="trace_hand_left_middle_tip" pos="0.022723 -0.003808 0" size="0.005" |
| rgba="1 0 0 1" /> |
| <site name="track_hand_left_middle_tip" pos="0.022723 -0.003808 0" size="0.005" |
| rgba="0 0 1 1" /> |
| <site name="left_middle_tip" pos="0.022723 -0.003808 0" quat="1 0 0 0" /> |
| </body> |
| </body> |
| </body> |
| </body> |
|
|
| <body name="left_pinky1y" pos="0.0687869 -0.00994033 -0.0432093" |
| quat="0.959155 -0.0168401 0.276261 -0.0584674"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_pinky1y" pos="0 0 0" axis="0 -1 0" range="-0.174533 0.174533" /> |
| <body name="left_pinky1z"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_pinky1z" pos="0 0 0" axis="0 0 -1" range="0 1.5708" /> |
| <geom quat="0.959155 0.0168401 -0.276261 0.0584674" type="mesh" contype="0" |
| conaffinity="0" |
| group="1" density="0" mesh="left_pinky1_vis" /> |
| <geom name="collision_hand_left_pinky_1" type="capsule" size="0.007 0.010" pos="0.010 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_pinky2" pos="0.0208927 0.0026189 -0.00153353" |
| quat="0.997398 -0.00215815 0.036279 0.0622646"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_pinky2" pos="0 0 0" axis="0 0 -1" range="0 1.74533" /> |
| <geom quat="0.950241 -0.000456125 -0.311514 -0.00139136" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_pinky2_vis" /> |
| <geom name="collision_hand_left_pinky_2" type="capsule" size="0.006 0.009" |
| pos="0.009 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_pinky3" pos="0.0189021 -0.00074651 0.00106698" |
| quat="0.999409 0.00047293 -0.028183 -0.0196984"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_pinky3" pos="0 0 0" axis="0 0 -1" range="0 1.39626" /> |
| <geom quat="0.958485 0.00519187 -0.284559 0.0174879" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_pinky3_vis" /> |
| <geom name="collision_hand_left_pinky_3" type="capsule" size="0.005 0.008" |
| pos="0.008 0 0" group="3" rgba="0 1 0 1" /> |
| <site name="trace_hand_left_pinky_tip" pos="0.016054 -0.004705 0" size="0.005" |
| rgba="1 0 0 1" /> |
| <site name="track_hand_left_pinky_tip" pos="0.016054 -0.004705 0" size="0.005" |
| rgba="0 0 1 1" /> |
| <site name="left_pinky_tip" pos="0.016054 -0.004705 0" quat="1 0 0 0" /> |
| </body> |
| </body> |
| </body> |
| </body> |
|
|
| <body name="left_ring1y" pos="0.0817355 -0.00395742 -0.0266732" |
| quat="0.987327 -0.0036119 0.157025 -0.0227106"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_ring1y" pos="0 0 0" axis="0 -1 0" range="-0.174533 0.174533" /> |
| <body name="left_ring1z"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_ring1z" pos="0 0 0" axis="0 0 -1" range="0 1.5708" /> |
| <geom quat="0.987327 0.0036119 -0.157025 0.0227106" type="mesh" contype="0" |
| conaffinity="0" |
| group="1" density="0" mesh="left_ring1_vis" /> |
| <geom name="collision_hand_left_ring_1" type="capsule" size="0.007 0.014" pos="0.014 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_ring2" pos="0.0283738 0.0033752 0.00393707" |
| quat="0.995918 -0.000882244 -0.0685799 0.0586873"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_ring2" pos="0 0 0" axis="0 0 -1" range="0 1.74533" /> |
| <geom quat="0.995395 -0.00318966 -0.0889052 -0.0357119" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_ring2_vis" /> |
| <geom name="collision_hand_left_ring_2" type="capsule" size="0.006 0.012" |
| pos="0.012 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_ring3" pos="0.0243171 -0.00343957 -0.0033447" |
| quat="0.995261 0.000120758 0.0677846 -0.0697243"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_ring3" pos="0 0 0" axis="0 0 -1" range="0 1.39626" /> |
| <geom quat="0.98714 0.00532482 -0.156183 0.033655" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_ring3_vis" /> |
| <geom name="collision_hand_left_ring_3" type="capsule" size="0.005 0.010" |
| pos="0.010 0 0" group="3" rgba="0 1 0 1" /> |
| <site name="trace_hand_left_ring_tip" pos="0.021453 -0.00486 0" size="0.005" |
| rgba="1 0 0 1" /> |
| <site name="track_hand_left_ring_tip" pos="0.021453 -0.00486 0" size="0.005" |
| rgba="0 0 1 1" /> |
| <site name="left_ring_tip" pos="0.021453 -0.00486 0" quat="1 0 0 0" /> |
| </body> |
| </body> |
| </body> |
| </body> |
|
|
| <body name="left_thumb1x" pos="0.0240897 -0.0155223 0.0258128" |
| quat="0.751793 0.497092 -0.432853 0.0185415"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_thumb1x" pos="0 0 0" axis="1 0 0" range="0 1.0472" /> |
| <body name="left_thumb1y"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_thumb1y" pos="0 0 0" axis="0 -1 0" range="-0.261799 1.0472" /> |
| <body name="left_thumb1z"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_thumb1z" pos="0 0 0" axis="0 0 -1" range="-1.0472 1.0472" /> |
| <geom quat="0.751793 -0.497092 0.432853 -0.0185414" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_thumb1_vis" /> |
| <geom name="collision_hand_left_thumb_1" type="capsule" size="0.008 0.014" |
| pos="0.014 0 0" |
| group="3" rgba="0 1 0 1" /> |
| <body name="left_thumb2y" pos="0.0277653 0.0087871 -0.00999011" |
| quat="0.975097 -0.00949146 0.164941 0.147951"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_thumb2y" pos="0 0 0" axis="0 -1 0" range="-0.174533 0.174533" /> |
| <body name="left_thumb2z"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_thumb2z" pos="0 0 0" axis="0 0 -1" range="0 1.5708" /> |
| <geom quat="0.806442 -0.410478 0.371794 -0.207191" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_thumb2_vis" /> |
| <geom name="collision_hand_left_thumb_2" type="capsule" size="0.007 0.012" |
| pos="0.012 0 0" group="3" rgba="0 1 0 1" /> |
| <body name="left_thumb3" pos="0.0251906 -0.00996365 0.00050434" |
| quat="0.982278 0.000921531 -0.00965077 -0.187179"> |
| <inertial pos="0 0 0" mass="0.02" diaginertia="1.6875e-06 1.6875e-06 1.6875e-06" /> |
| <joint name="left_j_thumb3" pos="0 0 0" axis="0 0 -1" range="0 1.39626" /> |
| <geom quat="0.826966 -0.475539 0.295964 -0.0489517" type="mesh" contype="0" |
| conaffinity="0" group="1" density="0" mesh="left_thumb3_vis" /> |
| <geom name="collision_hand_left_thumb_3" type="capsule" size="0.006 0.010" |
| pos="0.010 0 0" group="3" rgba="0 1 0 1" /> |
| <site name="trace_hand_left_thumb_tip" pos="0.026822 -0.00565 0" size="0.005" |
| rgba="1 0 0 1" /> |
| <site name="track_hand_left_thumb_tip" pos="0.026822 -0.00565 0" size="0.005" |
| rgba="0 0 1 1" /> |
| <site name="left_thumb_tip" pos="0.026822 -0.00565 0" quat="1 0 0 0" /> |
| </body> |
| </body> |
| </body> |
| </body> |
| </body> |
| </body> |
| </body> |
| </worldbody> |
|
|
| <actuator> |
| |
| <position name="left_pos_x" joint="left_pos_x" class="left_base_slide" /> |
| <position name="left_pos_y" joint="left_pos_y" class="left_base_slide" /> |
| <position name="left_pos_z" joint="left_pos_z" class="left_base_slide" /> |
| <position name="left_rot_x" joint="left_rot_x" class="left_base_hinge" /> |
| <position name="left_rot_y" joint="left_rot_y" class="left_base_hinge" /> |
| <position name="left_rot_z" joint="left_rot_z" class="left_base_hinge" /> |
|
|
| |
| <position name="left_j_index1y_position" joint="left_j_index1y" kp="300" /> |
| <position name="left_j_index1z_position" joint="left_j_index1z" kp="300" /> |
| <position name="left_j_index2_position" joint="left_j_index2" kp="300" /> |
| <position name="left_j_index3_position" joint="left_j_index3" kp="300" /> |
|
|
| |
| <position name="left_j_middle1y_position" joint="left_j_middle1y" kp="300" /> |
| <position name="left_j_middle1z_position" joint="left_j_middle1z" kp="300" /> |
| <position name="left_j_middle2_position" joint="left_j_middle2" kp="300" /> |
| <position name="left_j_middle3_position" joint="left_j_middle3" kp="300" /> |
|
|
| |
| <position name="left_j_pinky1y_position" joint="left_j_pinky1y" kp="300" /> |
| <position name="left_j_pinky1z_position" joint="left_j_pinky1z" kp="300" /> |
| <position name="left_j_pinky2_position" joint="left_j_pinky2" kp="300" /> |
| <position name="left_j_pinky3_position" joint="left_j_pinky3" kp="300" /> |
|
|
| |
| <position name="left_j_ring1y_position" joint="left_j_ring1y" kp="300" /> |
| <position name="left_j_ring1z_position" joint="left_j_ring1z" kp="300" /> |
| <position name="left_j_ring2_position" joint="left_j_ring2" kp="300" /> |
| <position name="left_j_ring3_position" joint="left_j_ring3" kp="300" /> |
|
|
| |
| <position name="left_j_thumb1x_position" joint="left_j_thumb1x" kp="300" /> |
| <position name="left_j_thumb1y_position" joint="left_j_thumb1y" kp="300" /> |
| <position name="left_j_thumb1z_position" joint="left_j_thumb1z" kp="300" /> |
| <position name="left_j_thumb2y_position" joint="left_j_thumb2y" kp="300" /> |
| <position name="left_j_thumb2z_position" joint="left_j_thumb2z" kp="300" /> |
| <position name="left_j_thumb3_position" joint="left_j_thumb3" kp="300" /> |
| </actuator> |
| </mujoco> |