Commit
·
b761f3d
1
Parent(s):
1523fb1
update robots
Browse files
robots/h1_simple_hand/mjcf/h1_simple_hand.xml
ADDED
|
@@ -0,0 +1,483 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<mujoco model="h1_simple_hand">
|
| 2 |
+
<compiler angle="radian" autolimits="true"/>
|
| 3 |
+
|
| 4 |
+
<default>
|
| 5 |
+
<default class="h1">
|
| 6 |
+
<geom type="mesh"/>
|
| 7 |
+
<joint damping="1" armature="0.1"/>
|
| 8 |
+
<default class="visual">
|
| 9 |
+
<geom contype="0" conaffinity="0" group="2" material="black"/>
|
| 10 |
+
</default>
|
| 11 |
+
<default class="collision">
|
| 12 |
+
<geom group="3" mass="0" density="0"/>
|
| 13 |
+
</default>
|
| 14 |
+
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
|
| 15 |
+
<default class="hip">
|
| 16 |
+
<position forcerange="-200 200" kp="200" kv="5"/>
|
| 17 |
+
</default>
|
| 18 |
+
<default class="knee">
|
| 19 |
+
<position forcerange="-300 300" kp="300" kv="6"/>
|
| 20 |
+
</default>
|
| 21 |
+
<default class="ankle">
|
| 22 |
+
<position forcerange="-40 40" kp="40" kv="2"/>
|
| 23 |
+
</default>
|
| 24 |
+
<default class="torso">
|
| 25 |
+
<position forcerange="-200 200" kp="300" kv="6"/>
|
| 26 |
+
</default>
|
| 27 |
+
<default class="shoulder1">
|
| 28 |
+
<position forcerange="-40 40" kp="100" kv="2"/>
|
| 29 |
+
</default>
|
| 30 |
+
<default class="shoulder2">
|
| 31 |
+
<position forcerange="-18 18" kp="100" kv="2"/>
|
| 32 |
+
</default>
|
| 33 |
+
<default class="elbow">
|
| 34 |
+
<position forcerange="-18 18" kp="100" kv="2"/>
|
| 35 |
+
</default>
|
| 36 |
+
</default>
|
| 37 |
+
</default>
|
| 38 |
+
|
| 39 |
+
<asset>
|
| 40 |
+
<!-- 天空盒:蓝色渐变 -->
|
| 41 |
+
<texture name="texsky" type="skybox" builtin="gradient"
|
| 42 |
+
rgb1="0.6 0.8 1" rgb2="0.1 0.4 0.8"
|
| 43 |
+
width="512" height="3072"/>
|
| 44 |
+
<material name="black" rgba="0.1 0.1 0.1 1"/>
|
| 45 |
+
<material name="white" rgba="1 1 1 1"/>
|
| 46 |
+
|
| 47 |
+
<mesh file="../../h1/mjcf/assets/pelvis.stl"/>
|
| 48 |
+
<mesh file="../../h1/mjcf/assets/left_hip_yaw_link.stl"/>
|
| 49 |
+
<mesh file="../../h1/mjcf/assets/left_hip_roll_link.stl"/>
|
| 50 |
+
<mesh file="../../h1/mjcf/assets/left_hip_pitch_link.stl"/>
|
| 51 |
+
<mesh file="../../h1/mjcf/assets/left_knee_link.stl"/>
|
| 52 |
+
<mesh file="../../h1/mjcf/assets/left_ankle_link.stl"/>
|
| 53 |
+
<mesh file="../../h1/mjcf/assets/right_hip_yaw_link.stl"/>
|
| 54 |
+
<mesh file="../../h1/mjcf/assets/right_hip_roll_link.stl"/>
|
| 55 |
+
<mesh file="../../h1/mjcf/assets/right_hip_pitch_link.stl"/>
|
| 56 |
+
<mesh file="../../h1/mjcf/assets/right_knee_link.stl"/>
|
| 57 |
+
<mesh file="../../h1/mjcf/assets/right_ankle_link.stl"/>
|
| 58 |
+
<mesh file="../../h1/mjcf/assets/torso_link.stl"/>
|
| 59 |
+
<mesh file="../../h1/mjcf/assets/left_shoulder_pitch_link.stl"/>
|
| 60 |
+
<mesh file="../../h1/mjcf/assets/left_shoulder_roll_link.stl"/>
|
| 61 |
+
<mesh file="../../h1/mjcf/assets/left_shoulder_yaw_link.stl"/>
|
| 62 |
+
<mesh file="../../h1/mjcf/assets/left_elbow_link.stl"/>
|
| 63 |
+
<mesh name="left_hand_link" file="../../h1/mjcf/assets/left_hand_link.stl"/>
|
| 64 |
+
<mesh name="L_hand_base_link" file="../../h1/mjcf/assets/L_hand_base_link.stl"/>
|
| 65 |
+
<mesh name="Link11_L" file="../../h1/mjcf/assets/Link11_L.stl"/>
|
| 66 |
+
<mesh name="Link12_L" file="../../h1/mjcf/assets/Link12_L.stl"/>
|
| 67 |
+
<mesh name="Link13_L" file="../../h1/mjcf/assets/Link13_L.stl"/>
|
| 68 |
+
<mesh name="Link14_L" file="../../h1/mjcf/assets/Link14_L.stl"/>
|
| 69 |
+
<mesh name="Link15_L" file="../../h1/mjcf/assets/Link15_L.stl"/>
|
| 70 |
+
<mesh name="Link16_L" file="../../h1/mjcf/assets/Link16_L.stl"/>
|
| 71 |
+
<mesh name="Link17_L" file="../../h1/mjcf/assets/Link17_L.stl"/>
|
| 72 |
+
<mesh name="Link18_L" file="../../h1/mjcf/assets/Link18_L.stl"/>
|
| 73 |
+
<mesh name="Link19_L" file="../../h1/mjcf/assets/Link19_L.stl"/>
|
| 74 |
+
<mesh name="Link20_L" file="../../h1/mjcf/assets/Link20_L.stl"/>
|
| 75 |
+
<mesh name="Link21_L" file="../../h1/mjcf/assets/Link21_L.stl"/>
|
| 76 |
+
<mesh name="Link22_L" file="../../h1/mjcf/assets/Link22_L.stl"/>
|
| 77 |
+
<mesh file="../../h1/mjcf/assets/right_shoulder_pitch_link.stl"/>
|
| 78 |
+
<mesh file="../../h1/mjcf/assets/right_shoulder_roll_link.stl"/>
|
| 79 |
+
<mesh file="../../h1/mjcf/assets/right_shoulder_yaw_link.stl"/>
|
| 80 |
+
<mesh file="../../h1/mjcf/assets/right_elbow_link.stl"/>
|
| 81 |
+
<mesh name="right_hand_link" file="../../h1/mjcf/assets/right_hand_link.stl"/>
|
| 82 |
+
<mesh name="R_hand_base_link" file="../../h1/mjcf/assets/R_hand_base_link.stl"/>
|
| 83 |
+
<mesh name="Link11_R" file="../../h1/mjcf/assets/Link11_R.stl"/>
|
| 84 |
+
<mesh name="Link12_R" file="../../h1/mjcf/assets/Link12_R.stl"/>
|
| 85 |
+
<mesh name="Link13_R" file="../../h1/mjcf/assets/Link13_R.stl"/>
|
| 86 |
+
<mesh name="Link14_R" file="../../h1/mjcf/assets/Link14_R.stl"/>
|
| 87 |
+
<mesh name="Link15_R" file="../../h1/mjcf/assets/Link15_R.stl"/>
|
| 88 |
+
<mesh name="Link16_R" file="../../h1/mjcf/assets/Link16_R.stl"/>
|
| 89 |
+
<mesh name="Link17_R" file="../../h1/mjcf/assets/Link17_R.stl"/>
|
| 90 |
+
<mesh name="Link18_R" file="../../h1/mjcf/assets/Link18_R.stl"/>
|
| 91 |
+
<mesh name="Link19_R" file="../../h1/mjcf/assets/Link19_R.stl"/>
|
| 92 |
+
<mesh name="Link20_R" file="../../h1/mjcf/assets/Link20_R.stl"/>
|
| 93 |
+
<mesh name="Link21_R" file="../../h1/mjcf/assets/Link21_R.stl"/>
|
| 94 |
+
<mesh name="Link22_R" file="../../h1/mjcf/assets/Link22_R.stl"/>
|
| 95 |
+
<mesh file="../../h1/mjcf/assets/logo_link.stl"/>
|
| 96 |
+
</asset>
|
| 97 |
+
|
| 98 |
+
<worldbody>
|
| 99 |
+
<light pos="0 0 10" castshadow="false" directional="true"
|
| 100 |
+
ambient="0.3 0.3 0.3" diffuse="0.7 0.7 0.7" specular="0.1 0.1 0.1"/>
|
| 101 |
+
|
| 102 |
+
<camera name="cam_kitchen" pos="-0.3 -2.5 2.5" xyaxes="1 0 0 0 0.5 1"/>
|
| 103 |
+
<body name="pelvis" pos="0 0 0" childclass="h1">
|
| 104 |
+
<site name="com" pos="0 0 0" rgba="1 0 0 0" size="0.01"/>
|
| 105 |
+
<camera name="cam_default" pos="2 3 0.8" mode="trackcom" xyaxes="-1 0.5 0 -0.2 -0.2 1"/>
|
| 106 |
+
<camera name="cam_maze" pos="3 3 3" mode="trackcom" xyaxes="-0.5 0.5 0 -0.4 -0.4 1"/>
|
| 107 |
+
<camera name="cam_tabletop" pos="2.5 2 1.5" mode="trackcom" xyaxes="-0.5 0.5 0 -0.4 -0.4 1"/>
|
| 108 |
+
<camera name="cam_hurdle" pos="-3 3 3" mode="trackcom" xyaxes="-0.5 -0.5 0 0.4 -0.4 1"/>
|
| 109 |
+
<camera name="cam_basketball" pos="-1.8 3.5 3" mode="trackcom" xyaxes="-0.4 -0.5 0 0.4 -0.4 1"/>
|
| 110 |
+
<camera name="cam_hand_visible" pos="-1.5 1.5 0.5" mode="trackcom" xyaxes="-0.8 -1 0 0 -0.3 1"/>
|
| 111 |
+
<camera name="cam_inhand" pos="1.5 1.5 0.5" mode="trackcom" xyaxes="-1 0.8 0 0 -0.3 1"/>
|
| 112 |
+
<inertial pos="-0.0002 4e-05 -0.04522" quat="0.498303 0.499454 -0.500496 0.501741" mass="5.39"
|
| 113 |
+
diaginertia="0.0490211 0.0445821 0.00824619"/>
|
| 114 |
+
<geom class="visual" mesh="pelvis"/>
|
| 115 |
+
<geom class="collision" mesh="pelvis"/>
|
| 116 |
+
<body name="left_hip_yaw_link" pos="0 0.0875 -0.1742">
|
| 117 |
+
<inertial pos="-0.04923 0.0001 0.0072" quat="0.69699 0.219193 0.233287 0.641667" mass="2.244"
|
| 118 |
+
diaginertia="0.00304494 0.00296885 0.00189201"/>
|
| 119 |
+
<joint name="left_hip_yaw" axis="0 0 1" range="-0.43 0.43"/>
|
| 120 |
+
<geom class="visual" mesh="left_hip_yaw_link"/>
|
| 121 |
+
<geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/>
|
| 122 |
+
<body name="left_hip_roll_link" pos="0.039468 0 0">
|
| 123 |
+
<inertial pos="-0.0058 -0.00319 -9e-05" quat="0.0438242 0.70721 -0.0729075 0.701867" mass="2.232"
|
| 124 |
+
diaginertia="0.00243264 0.00225325 0.00205492"/>
|
| 125 |
+
<joint name="left_hip_roll" axis="1 0 0" range="-0.43 0.43"/>
|
| 126 |
+
<geom class="visual" mesh="left_hip_roll_link"/>
|
| 127 |
+
<geom class="collision" mesh="left_hip_roll_link"/>
|
| 128 |
+
<body name="left_hip_pitch_link" pos="0 0.11536 0">
|
| 129 |
+
<inertial pos="0.00746 -0.02346 -0.08193" quat="0.979828 0.0513522 -0.0169854 -0.192382" mass="4.152"
|
| 130 |
+
diaginertia="0.0829503 0.0821457 0.00510909"/>
|
| 131 |
+
<joint name="left_hip_pitch" axis="0 1 0" range="-3.14 2.53"/>
|
| 132 |
+
<geom class="visual" mesh="left_hip_pitch_link"/>
|
| 133 |
+
<geom class="collision" mesh="left_hip_pitch_link"/>
|
| 134 |
+
<body name="left_knee_link" pos="0 0 -0.4">
|
| 135 |
+
<inertial pos="-0.00136 -0.00512 -0.1384" quat="0.626132 -0.034227 -0.0416277 0.777852" mass="1.721"
|
| 136 |
+
diaginertia="0.0125237 0.0123104 0.0019428"/>
|
| 137 |
+
<joint name="left_knee" axis="0 1 0" range="-0.26 2.05"/>
|
| 138 |
+
<geom class="visual" mesh="left_knee_link"/>
|
| 139 |
+
<geom class="collision" mesh="left_knee_link"/>
|
| 140 |
+
<body name="left_ankle_link" pos="0 0 -0.4">
|
| 141 |
+
<inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
|
| 142 |
+
diaginertia="0.00362 0.00355701 0.000149987"/>
|
| 143 |
+
<joint name="left_ankle" axis="0 1 0" range="-0.87 0.52"/>
|
| 144 |
+
<geom class="visual" mesh="left_ankle_link"/>
|
| 145 |
+
<site name="left_foot" pos="0. 0 -0.05" rgba="0 1 0 1" size="0.001"/>
|
| 146 |
+
<geom class="collision" mesh="left_ankle_link"/>
|
| 147 |
+
</body>
|
| 148 |
+
</body>
|
| 149 |
+
</body>
|
| 150 |
+
</body>
|
| 151 |
+
</body>
|
| 152 |
+
<body name="right_hip_yaw_link" pos="0 -0.0875 -0.1742">
|
| 153 |
+
<inertial pos="-0.04923 -0.0001 0.0072" quat="0.641667 0.233287 0.219193 0.69699" mass="2.244"
|
| 154 |
+
diaginertia="0.00304494 0.00296885 0.00189201"/>
|
| 155 |
+
<joint name="right_hip_yaw" axis="0 0 1" range="-0.43 0.43"/>
|
| 156 |
+
<geom class="visual" mesh="right_hip_yaw_link"/>
|
| 157 |
+
<geom size="0.06 0.035" pos="-0.067 0 0" quat="0.707123 0 0.70709 0" type="cylinder" class="collision"/>
|
| 158 |
+
<body name="right_hip_roll_link" pos="0.039468 0 0">
|
| 159 |
+
<inertial pos="-0.0058 0.00319 -9e-05" quat="-0.0438242 0.70721 0.0729075 0.701867" mass="2.232"
|
| 160 |
+
diaginertia="0.00243264 0.00225325 0.00205492"/>
|
| 161 |
+
<joint name="right_hip_roll" axis="1 0 0" range="-0.43 0.43"/>
|
| 162 |
+
<geom class="visual" mesh="right_hip_roll_link"/>
|
| 163 |
+
<geom class="collision" mesh="right_hip_roll_link"/>
|
| 164 |
+
<body name="right_hip_pitch_link" pos="0 -0.11536 0">
|
| 165 |
+
<inertial pos="0.00746 0.02346 -0.08193" quat="0.979828 -0.0513522 -0.0169854 0.192382" mass="4.152"
|
| 166 |
+
diaginertia="0.0829503 0.0821457 0.00510909"/>
|
| 167 |
+
<joint name="right_hip_pitch" axis="0 1 0" range="-3.14 2.53"/>
|
| 168 |
+
<geom class="visual" mesh="right_hip_pitch_link"/>
|
| 169 |
+
<geom class="collision" mesh="right_hip_pitch_link"/>
|
| 170 |
+
<body name="right_knee_link" pos="0 0 -0.4">
|
| 171 |
+
<inertial pos="-0.00136 0.00512 -0.1384" quat="0.777852 -0.0416277 -0.034227 0.626132" mass="1.721"
|
| 172 |
+
diaginertia="0.0125237 0.0123104 0.0019428"/>
|
| 173 |
+
<joint name="right_knee" axis="0 1 0" range="-0.26 2.05"/>
|
| 174 |
+
<geom class="visual" mesh="right_knee_link"/>
|
| 175 |
+
<geom class="collision" mesh="right_knee_link"/>
|
| 176 |
+
<body name="right_ankle_link" pos="0 0 -0.4">
|
| 177 |
+
<inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
|
| 178 |
+
diaginertia="0.00362 0.00355701 0.000149987"/>
|
| 179 |
+
<joint name="right_ankle" axis="0 1 0" range="-0.87 0.52"/>
|
| 180 |
+
<geom class="visual" mesh="right_ankle_link"/>
|
| 181 |
+
<site name="right_foot" pos="0. 0 -0.05" rgba="0 1 0 1" size="0.001"/>
|
| 182 |
+
<geom class="collision" mesh="right_ankle_link"/>
|
| 183 |
+
</body>
|
| 184 |
+
</body>
|
| 185 |
+
</body>
|
| 186 |
+
</body>
|
| 187 |
+
</body>
|
| 188 |
+
<body name="torso_link">
|
| 189 |
+
<site name="left_eye" pos="0.1 0.03 0.65" rgba="1 1 1 1" size="0.01" zaxis="1 0 0" group="1"/>
|
| 190 |
+
<camera name="left_eye_camera" pos="0.1 0.03 0.65" xyaxes="0 -1 0 0 0 1"/>
|
| 191 |
+
<site name="right_eye" pos="0.1 -0.03 0.65" rgba="1 1 1 1" size="0.01" zaxis="1 0 0" group="1"/>
|
| 192 |
+
<camera name="right_eye_camera" pos="0.1 -0.03 0.65" xyaxes="0 -1 0 0 0 1"/>
|
| 193 |
+
<inertial pos="0.000489 0.002797 0.20484" quat="0.999989 -0.00130808 -0.00282289 -0.00349105" mass="17.789"
|
| 194 |
+
diaginertia="0.487315 0.409628 0.127837"/>
|
| 195 |
+
<joint name="torso" axis="0 0 1" range="-2.35 2.35"/>
|
| 196 |
+
<geom class="visual" mesh="torso_link"/>
|
| 197 |
+
<geom class="collision" mesh="torso_link"/>
|
| 198 |
+
<geom class="visual" material="white" mesh="logo_link"/>
|
| 199 |
+
<site name="head" class="visual" size="0.01" pos="0 0 0.7" rgba="1 1 1 1"/>
|
| 200 |
+
<site name="imu" size="0.01" pos="-0.04452 -0.01891 0.27756"/>
|
| 201 |
+
<body name="left_shoulder_pitch_link" pos="0.0055 0.15535 0.42999" quat="0.976296 0.216438 0 0">
|
| 202 |
+
<inertial pos="0.005045 0.053657 -0.015715" quat="0.814858 0.579236 -0.0201072 -0.00936488" mass="1.033"
|
| 203 |
+
diaginertia="0.00129936 0.000987113 0.000858198"/>
|
| 204 |
+
<joint name="left_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/>
|
| 205 |
+
<geom class="visual" mesh="left_shoulder_pitch_link"/>
|
| 206 |
+
<geom class="collision" mesh="left_shoulder_pitch_link"/>
|
| 207 |
+
<body name="left_shoulder_roll_link" pos="-0.0055 0.0565 -0.0165" quat="0.976296 -0.216438 0 0">
|
| 208 |
+
<inertial pos="0.000679 0.00115 -0.094076" quat="0.732491 0.00917179 0.0766656 0.676384" mass="0.793"
|
| 209 |
+
diaginertia="0.00170388 0.00158256 0.00100336"/>
|
| 210 |
+
<joint name="left_shoulder_roll" axis="1 0 0" range="-0.34 3.11"/>
|
| 211 |
+
<geom class="visual" mesh="left_shoulder_roll_link"/>
|
| 212 |
+
<geom class="collision" mesh="left_shoulder_roll_link"/>
|
| 213 |
+
<body name="left_shoulder_yaw_link" pos="0 0 -0.1343">
|
| 214 |
+
<inertial pos="0.01365 0.002767 -0.16266" quat="0.703042 -0.0331229 -0.0473362 0.708798" mass="0.839"
|
| 215 |
+
diaginertia="0.00408038 0.00370367 0.000622687"/>
|
| 216 |
+
<joint name="left_shoulder_yaw" axis="0 0 1" range="-1.3 4.45"/>
|
| 217 |
+
<geom class="visual" mesh="left_shoulder_yaw_link"/>
|
| 218 |
+
<geom class="collision" mesh="left_shoulder_yaw_link"/>
|
| 219 |
+
<body name="left_elbow_link" pos="0.0185 0 -0.198">
|
| 220 |
+
<inertial pos="0.15908 -0.000144 -0.015776" quat="0.0765232 0.720327 0.0853116 0.684102" mass="0.669"
|
| 221 |
+
diaginertia="0.00601829 0.00600579 0.000408305"/>
|
| 222 |
+
<joint name="left_elbow" pos="0 0 0" axis="0 1 0" range="-1.25 2.61"/>
|
| 223 |
+
<geom class="visual" mesh="left_elbow_link"/>
|
| 224 |
+
<geom class="collision" mesh="left_elbow_link"/>
|
| 225 |
+
<site name="left_hand" pos="0.2605 0 -0.0185" rgba="0 1 0 1" size="0.01"/>
|
| 226 |
+
<body name="left_hand_link" pos="0.2605 0 -0.0185">
|
| 227 |
+
<inertial pos="0.0631874 -0.00232969 -0.00176135" quat="0.509356 0.489591 0.510242 0.490418" mass="0.15543" diaginertia="0.000179349 0.000133079 8.74084e-05"/>
|
| 228 |
+
<joint name="left_hand" pos="0 0 0" axis="1 0 0" range="-3.05433 3.05433" damping="0.5" frictionloss="0.1"/>
|
| 229 |
+
<geom type="mesh" class="visual" mesh="left_hand_link"/>
|
| 230 |
+
<geom type="mesh" class="collision" mesh="left_hand_link"/>
|
| 231 |
+
<geom pos="0.003 0 0" quat="0.707107 0 0 0.707107" type="mesh" class="visual" mesh="L_hand_base_link"/>
|
| 232 |
+
<geom pos="0.003 0 0" quat="0.707107 0 0 0.707107" type="mesh" class="collision" mesh="L_hand_base_link"/>
|
| 233 |
+
<body name="L_thumb_proximal_base" pos="0.0721 -0.01696 0.02045" quat="-2.59735e-06 0.707107 0 0.707107">
|
| 234 |
+
<inertial pos="0.0048817 0.00038782 -0.00722" quat="0.445981 0.352284 0.495833 0.656617" mass="0.0018869" diaginertia="8.66031e-08 6.87331e-08 4.94199e-08"/>
|
| 235 |
+
<joint name="L_thumb_proximal_yaw" pos="0 0 0" axis="0 0 1" range="-0.1 1.3" damping="0.5" frictionloss="0.1"/>
|
| 236 |
+
<geom type="mesh" class="visual" mesh="Link11_L"/>
|
| 237 |
+
<geom type="mesh" class="collision" mesh="Link11_L"/>
|
| 238 |
+
<body name="L_thumb_proximal" pos="0.0099867 0.0098242 -0.0089" quat="0.704571 -0.704573 -0.0598169 0.0598167">
|
| 239 |
+
<inertial pos="0.021936 -0.01279 -0.0080386" quat="0.25452 0.660687 -0.251949 0.659723" mass="0.0066101" diaginertia="2.78701e-06 2.44024e-06 8.6466e-07"/>
|
| 240 |
+
<joint name="L_thumb_proximal_pitch" pos="0 0 0" axis="0 0 -1" range="-0.1 0.6" damping="0.5" frictionloss="0.1"/>
|
| 241 |
+
<geom type="mesh" class="visual" mesh="Link12_L"/>
|
| 242 |
+
<geom type="mesh" class="collision" mesh="Link12_L"/>
|
| 243 |
+
<body name="L_thumb_intermediate" pos="0.04407 -0.034553 -0.0008">
|
| 244 |
+
<inertial pos="0.0095531 0.0016282 -0.0072002" quat="0.30738 0.636732 -0.307526 0.636803" mass="0.0037844" diaginertia="4.6532e-07 4.48114e-07 2.45646e-07"/>
|
| 245 |
+
<joint name="L_thumb_intermediate" pos="0 0 0" axis="0 0 -1" range="0 0.8" damping="0.5" frictionloss="0.1"/>
|
| 246 |
+
<geom type="mesh" class="visual" mesh="Link13_L"/>
|
| 247 |
+
<geom type="mesh" class="collision" mesh="Link13_L"/>
|
| 248 |
+
<body name="L_thumb_distal" pos="0.020248 -0.010156 -0.0012">
|
| 249 |
+
<inertial pos="0.0092888 -0.004953 -0.0060033" quat="0.266264 0.65596 -0.262836 0.655544" mass="0.003344" diaginertia="2.0026e-07 1.95246e-07 8.1594e-08"/>
|
| 250 |
+
<joint name="L_thumb_distal" pos="0 0 0" axis="0 0 -1" range="0 1.2" damping="0.5" frictionloss="0.1"/>
|
| 251 |
+
<geom type="mesh" class="visual" mesh="Link14_L"/>
|
| 252 |
+
<geom type="mesh" class="collision" mesh="Link14_L"/>
|
| 253 |
+
</body>
|
| 254 |
+
</body>
|
| 255 |
+
</body>
|
| 256 |
+
</body>
|
| 257 |
+
<body name="L_index_proximal" pos="0.13953 0.00028533 0.032268" quat="0.706999 -0.0123409 -0.0123409 0.706999">
|
| 258 |
+
<inertial pos="0.0012971 -0.011934 -0.0059998" quat="0.489677 0.510115 -0.489692 0.510099" mass="0.0042405" diaginertia="6.9402e-07 6.62904e-07 2.10916e-07"/>
|
| 259 |
+
<joint name="L_index_proximal" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 260 |
+
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 11" mesh="Link15_L"/>
|
| 261 |
+
<geom type="mesh" class="collision" mesh="Link15_L"/>
|
| 262 |
+
<body name="L_index_intermediate" pos="-0.0024229 -0.032041 -0.001">
|
| 263 |
+
<inertial pos="0.0021753 -0.019567 -0.005" quat="0.528694 0.469555 -0.528694 0.469555" mass="0.0045682" diaginertia="7.8176e-07 7.72427e-07 8.47209e-08"/>
|
| 264 |
+
<joint name="L_index_intermediate" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 265 |
+
<geom type="mesh" class="visual" mesh="Link16_L"/>
|
| 266 |
+
<geom type="mesh" class="collision" mesh="Link16_L"/>
|
| 267 |
+
</body>
|
| 268 |
+
</body>
|
| 269 |
+
<body name="L_middle_proximal" pos="0.1401 0.00028533 0.01295" quat="0.707107 0 0 0.707107">
|
| 270 |
+
<inertial pos="0.0012971 -0.011934 -0.0059999" quat="0.489677 0.510115 -0.489692 0.510099" mass="0.0042405" diaginertia="6.9402e-07 6.62904e-07 2.10916e-07"/>
|
| 271 |
+
<joint name="L_middle_proximal" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 272 |
+
<geom type="mesh" class="visual" mesh="Link17_L"/>
|
| 273 |
+
<geom type="mesh" class="collision" mesh="Link17_L"/>
|
| 274 |
+
<body name="L_middle_intermediate" pos="-0.0024229 -0.032041 -0.001">
|
| 275 |
+
<inertial pos="0.001921 -0.020796 -0.0049999" quat="0.531603 0.466115 -0.531728 0.466262" mass="0.0050397" diaginertia="9.8385e-07 9.73288e-07 9.14016e-08"/>
|
| 276 |
+
<joint name="L_middle_intermediate" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 277 |
+
<geom type="mesh" class="visual" mesh="Link18_L"/>
|
| 278 |
+
<geom type="mesh" class="collision" mesh="Link18_L"/>
|
| 279 |
+
</body>
|
| 280 |
+
</body>
|
| 281 |
+
<body name="L_ring_proximal" pos="0.13991 0.00028533 -0.0062872" quat="0.706864 0.0185099 0.0185099 0.706864">
|
| 282 |
+
<inertial pos="0.0012971 -0.011934 -0.0059999" quat="0.489677 0.510114 -0.489692 0.510099" mass="0.0042405" diaginertia="6.9402e-07 6.62904e-07 2.10916e-07"/>
|
| 283 |
+
<joint name="L_ring_proximal" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 284 |
+
<geom type="mesh" class="visual" mesh="Link19_L"/>
|
| 285 |
+
<geom type="mesh" class="collision" mesh="Link19_L"/>
|
| 286 |
+
<body name="L_ring_intermediate" pos="-0.0024229 -0.032041 -0.001">
|
| 287 |
+
<inertial pos="0.0021753 -0.019567 -0.005" quat="0.528694 0.469556 -0.528694 0.469556" mass="0.0045682" diaginertia="7.8176e-07 7.72437e-07 8.47208e-08"/>
|
| 288 |
+
<joint name="L_ring_intermediate" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 289 |
+
<geom type="mesh" class="visual" mesh="Link20_L"/>
|
| 290 |
+
<geom type="mesh" class="collision" mesh="Link20_L"/>
|
| 291 |
+
</body>
|
| 292 |
+
</body>
|
| 293 |
+
<body name="L_pinky_proximal" pos="0.13871 0.00028533 -0.025488" quat="0.706138 0.0370072 0.0370072 0.706138">
|
| 294 |
+
<inertial pos="0.0012971 -0.011934 -0.0059999" quat="0.489677 0.510114 -0.489692 0.510099" mass="0.0042405" diaginertia="6.9402e-07 6.62904e-07 2.10916e-07"/>
|
| 295 |
+
<joint name="L_pinky_proximal" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 296 |
+
<geom type="mesh" class="visual" mesh="Link21_L"/>
|
| 297 |
+
<geom type="mesh" class="collision" mesh="Link21_L"/>
|
| 298 |
+
<body name="L_pinky_intermediate" pos="-0.0024229 -0.032041 -0.001">
|
| 299 |
+
<inertial pos="0.0024788 -0.016208 -0.0050001" quat="0.526797 0.471683 -0.526793 0.471687" mass="0.0036036" diaginertia="4.4881e-07 4.43809e-07 6.5736e-08"/>
|
| 300 |
+
<joint name="L_pinky_intermediate" pos="0 0 0" axis="0 0 -1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 301 |
+
<geom type="mesh" class="visual" mesh="Link22_L"/>
|
| 302 |
+
<geom type="mesh" class="collision" mesh="Link22_L"/>
|
| 303 |
+
</body>
|
| 304 |
+
</body>
|
| 305 |
+
</body>
|
| 306 |
+
</body>
|
| 307 |
+
</body>
|
| 308 |
+
</body>
|
| 309 |
+
</body>
|
| 310 |
+
<body name="right_shoulder_pitch_link" pos="0.0055 -0.15535 0.42999" quat="0.976296 -0.216438 0 0">
|
| 311 |
+
<inertial pos="0.005045 -0.053657 -0.015715" quat="0.579236 0.814858 0.00936488 0.0201072" mass="1.033"
|
| 312 |
+
diaginertia="0.00129936 0.000987113 0.000858198"/>
|
| 313 |
+
<joint name="right_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/>
|
| 314 |
+
<geom class="visual" mesh="right_shoulder_pitch_link"/>
|
| 315 |
+
<geom class="collision" mesh="right_shoulder_pitch_link"/>
|
| 316 |
+
<body name="right_shoulder_roll_link" pos="-0.0055 -0.0565 -0.0165" quat="0.976296 0.216438 0 0">
|
| 317 |
+
<inertial pos="0.000679 -0.00115 -0.094076" quat="0.676384 0.0766656 0.00917179 0.732491" mass="0.793"
|
| 318 |
+
diaginertia="0.00170388 0.00158256 0.00100336"/>
|
| 319 |
+
<joint name="right_shoulder_roll" axis="1 0 0" range="-3.11 0.34"/>
|
| 320 |
+
<geom class="visual" mesh="right_shoulder_roll_link"/>
|
| 321 |
+
<geom class="collision" mesh="right_shoulder_roll_link"/>
|
| 322 |
+
<body name="right_shoulder_yaw_link" pos="0 0 -0.1343">
|
| 323 |
+
<inertial pos="0.01365 -0.002767 -0.16266" quat="0.708798 -0.0473362 -0.0331229 0.703042" mass="0.839"
|
| 324 |
+
diaginertia="0.00408038 0.00370367 0.000622687"/>
|
| 325 |
+
<joint name="right_shoulder_yaw" axis="0 0 1" range="-4.45 1.3"/>
|
| 326 |
+
<geom class="visual" mesh="right_shoulder_yaw_link"/>
|
| 327 |
+
<geom class="collision" mesh="right_shoulder_yaw_link"/>
|
| 328 |
+
<body name="right_elbow_link" pos="0.0185 0 -0.198">
|
| 329 |
+
<inertial pos="0.15908 0.000144 -0.015776" quat="-0.0765232 0.720327 -0.0853116 0.684102" mass="0.669"
|
| 330 |
+
diaginertia="0.00601829 0.00600579 0.000408305"/>
|
| 331 |
+
<joint name="right_elbow" pos="0 0 0" axis="0 1 0" range="-1.25 2.61"/>
|
| 332 |
+
<geom class="visual" mesh="right_elbow_link"/>
|
| 333 |
+
<geom class="collision" mesh="right_elbow_link"/>
|
| 334 |
+
<site name="right_hand" pos="0.2605 0 -0.0185" rgba="0 1 0 1" size="0.01"/>
|
| 335 |
+
<body name="right_hand_link" pos="0.2605 0 -0.0185">
|
| 336 |
+
<inertial pos="0.0631874 0.00230731 -0.00178328" quat="0.490597 0.510024 0.489386 0.509599" mass="0.15543" diaginertia="0.00017876 0.000132509 8.7405e-05"/>
|
| 337 |
+
<joint name="right_hand" pos="0 0 0" axis="1 0 0" range="-3.05433 3.05433" damping="0.5" frictionloss="0.1"/>
|
| 338 |
+
<geom type="mesh" class="visual" mesh="right_hand_link"/>
|
| 339 |
+
<geom type="mesh" class="collision" mesh="right_hand_link"/>
|
| 340 |
+
<geom pos="0.003 0 0" quat="0 0.707107 -0.707107 0" type="mesh" class="visual" mesh="R_hand_base_link"/>
|
| 341 |
+
<geom pos="0.003 0 0" quat="0 0.707107 -0.707107 0" type="mesh" class="collision" mesh="R_hand_base_link"/>
|
| 342 |
+
<body name="R_thumb_proximal_base" pos="0.0721 0.01696 0.02045" quat="-0.707107 -2.59735e-06 -0.707107 0">
|
| 343 |
+
<inertial pos="-0.0048064 0.0009382 -0.00757" quat="0.515015 0.680854 0.408023 0.323596" mass="0.0018869" diaginertia="8.66026e-08 6.8732e-08 4.94194e-08"/>
|
| 344 |
+
<joint name="R_thumb_proximal_yaw" pos="0 0 0" axis="0 0 -1" range="-0.1 1.3" damping="0.5" frictionloss="0.1"/>
|
| 345 |
+
<geom type="mesh" class="visual" mesh="Link11_R"/>
|
| 346 |
+
<geom type="mesh" class="collision" mesh="Link11_R"/>
|
| 347 |
+
<body name="R_thumb_proximal" pos="-0.0088099 0.010892 -0.00925" quat="0.0996843 0.0996847 0.700046 0.700044">
|
| 348 |
+
<inertial pos="0.021932 0.012785 -0.0080386" quat="-0.254474 0.660716 0.251893 0.659733" mass="0.0066075" diaginertia="2.78601e-06 2.43933e-06 8.64566e-07"/>
|
| 349 |
+
<joint name="R_thumb_proximal_pitch" pos="0 0 0" axis="0 0 1" range="-0.1 0.6" damping="0.5" frictionloss="0.1"/>
|
| 350 |
+
<geom type="mesh" class="visual" mesh="Link12_R"/>
|
| 351 |
+
<geom type="mesh" class="collision" mesh="Link12_R"/>
|
| 352 |
+
<body name="R_thumb_intermediate" pos="0.04407 0.034553 -0.0008">
|
| 353 |
+
<inertial pos="0.0095544 -0.0016282 -0.0071997" quat="0.636718 0.307389 -0.636802 0.307548" mass="0.0037847" diaginertia="4.6531e-07 4.48089e-07 2.45661e-07"/>
|
| 354 |
+
<joint name="R_thumb_intermediate" pos="0 0 0" axis="0 0 1" range="0 0.8" damping="0.5" frictionloss="0.1"/>
|
| 355 |
+
<geom type="mesh" class="visual" mesh="Link13_R"/>
|
| 356 |
+
<geom type="mesh" class="collision" mesh="Link13_R"/>
|
| 357 |
+
<body name="R_thumb_distal" pos="0.020248 0.010156 -0.0012">
|
| 358 |
+
<inertial pos="0.0092888 0.0049529 -0.0060033" quat="-0.266294 0.655967 0.262806 0.655537" mass="0.0033441" diaginertia="2.0026e-07 1.95247e-07 8.1593e-08"/>
|
| 359 |
+
<joint name="R_thumb_distal" pos="0 0 0" axis="0 0 1" range="0 1.2" damping="0.5" frictionloss="0.1"/>
|
| 360 |
+
<geom type="mesh" class="visual" mesh="Link14_R"/>
|
| 361 |
+
<geom type="mesh" class="collision" mesh="Link14_R"/>
|
| 362 |
+
</body>
|
| 363 |
+
</body>
|
| 364 |
+
</body>
|
| 365 |
+
</body>
|
| 366 |
+
<body name="R_index_proximal" pos="0.13953 -0.00028533 0.032268" quat="0.706999 0.0123358 -0.0123358 -0.706999">
|
| 367 |
+
<inertial pos="0.0012259 0.011942 -0.0060001" quat="0.50867 0.49121 -0.508643 0.491172" mass="0.0042403" diaginertia="6.9398e-07 6.62871e-07 2.10909e-07"/>
|
| 368 |
+
<joint name="R_index_proximal" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 369 |
+
<geom type="mesh" class="visual" mesh="Link15_R"/>
|
| 370 |
+
<geom type="mesh" class="collision" mesh="Link15_R"/>
|
| 371 |
+
<body name="R_index_intermediate" pos="-0.0026138 0.032026 -0.001">
|
| 372 |
+
<inertial pos="0.0019697 0.019589 -0.005" quat="0.466773 0.531152 -0.466773 0.531153" mass="0.0045683" diaginertia="7.8179e-07 7.72465e-07 8.47212e-08"/>
|
| 373 |
+
<joint name="R_index_intermediate" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 374 |
+
<geom type="mesh" class="visual" mesh="Link16_R"/>
|
| 375 |
+
<geom type="mesh" class="collision" mesh="Link16_R"/>
|
| 376 |
+
</body>
|
| 377 |
+
</body>
|
| 378 |
+
<body name="R_middle_proximal" pos="0.1401 -0.00028533 0.01295" quat="0.707107 -2.59735e-06 2.59735e-06 -0.707107">
|
| 379 |
+
<inertial pos="0.001297 0.011934 -0.0060001" quat="0.510131 0.489693 -0.510105 0.489653" mass="0.0042403" diaginertia="6.9397e-07 6.62865e-07 2.10915e-07"/>
|
| 380 |
+
<joint name="R_middle_proximal" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 381 |
+
<geom type="mesh" class="visual" mesh="Link17_R"/>
|
| 382 |
+
<geom type="mesh" class="collision" mesh="Link17_R"/>
|
| 383 |
+
<body name="R_middle_intermediate" pos="-0.0024229 0.032041 -0.001">
|
| 384 |
+
<inertial pos="0.001921 0.020796 -0.005" quat="0.466148 0.531627 -0.466229 0.531705" mass="0.0050396" diaginertia="9.8384e-07 9.73279e-07 9.14014e-08"/>
|
| 385 |
+
<joint name="R_middle_intermediate" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 386 |
+
<geom type="mesh" class="visual" mesh="Link18_R"/>
|
| 387 |
+
<geom type="mesh" class="collision" mesh="Link18_R"/>
|
| 388 |
+
</body>
|
| 389 |
+
</body>
|
| 390 |
+
<body name="R_ring_proximal" pos="0.13991 -0.00028533 -0.0062872" quat="-0.706864 0.0185215 -0.0185215 0.706864">
|
| 391 |
+
<inertial pos="0.001297 0.011934 -0.0060002" quat="0.510129 0.489691 -0.510107 0.489654" mass="0.0042403" diaginertia="6.9397e-07 6.62865e-07 2.10915e-07"/>
|
| 392 |
+
<joint name="R_ring_proximal" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 393 |
+
<geom type="mesh" class="visual" mesh="Link19_R"/>
|
| 394 |
+
<geom type="mesh" class="collision" mesh="Link19_R"/>
|
| 395 |
+
<body name="R_ring_intermediate" pos="-0.0024229 0.032041 -0.001">
|
| 396 |
+
<inertial pos="0.0021753 0.019567 -0.005" quat="0.469554 0.528695 -0.469554 0.528695" mass="0.0045683" diaginertia="7.8177e-07 7.72448e-07 8.4722e-08"/>
|
| 397 |
+
<joint name="R_ring_intermediate" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 398 |
+
<geom type="mesh" class="visual" mesh="Link20_R"/>
|
| 399 |
+
<geom type="mesh" class="collision" mesh="Link20_R"/>
|
| 400 |
+
</body>
|
| 401 |
+
</body>
|
| 402 |
+
<body name="R_pinky_proximal" pos="0.13871 -0.00028533 -0.025488" quat="-0.706138 0.0369975 -0.0369975 0.706138">
|
| 403 |
+
<inertial pos="0.001297 0.011934 -0.0060001" quat="0.51013 0.489693 -0.510106 0.489653" mass="0.0042403" diaginertia="6.9397e-07 6.62865e-07 2.10915e-07"/>
|
| 404 |
+
<joint name="R_pinky_proximal" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 405 |
+
<geom type="mesh" class="visual" mesh="Link21_R"/>
|
| 406 |
+
<geom type="mesh" class="collision" mesh="Link21_R"/>
|
| 407 |
+
<body name="R_pinky_intermediate" pos="-0.0024229 0.032041 -0.001">
|
| 408 |
+
<inertial pos="0.0024748 0.016203 -0.0050031" quat="0.47398 0.528862 -0.469291 0.524799" mass="0.0035996" diaginertia="4.4867e-07 4.43723e-07 6.56538e-08"/>
|
| 409 |
+
<joint name="R_pinky_intermediate" pos="0 0 0" axis="0 0 1" range="0 1.7" damping="0.5" frictionloss="0.1"/>
|
| 410 |
+
<geom type="mesh" class="visual" mesh="Link22_R"/>
|
| 411 |
+
<geom type="mesh" class="collision" mesh="Link22_R"/>
|
| 412 |
+
</body>
|
| 413 |
+
</body>
|
| 414 |
+
</body>
|
| 415 |
+
</body>
|
| 416 |
+
</body>
|
| 417 |
+
</body>
|
| 418 |
+
</body>
|
| 419 |
+
</body>
|
| 420 |
+
</body>
|
| 421 |
+
</worldbody>
|
| 422 |
+
|
| 423 |
+
<actuator>
|
| 424 |
+
<position name="left_hip_yaw" joint="left_hip_yaw" ctrlrange="-0.43 0.43" class="hip" />
|
| 425 |
+
<position name="left_hip_roll" joint="left_hip_roll" ctrlrange="-0.43 0.43" class="hip" />
|
| 426 |
+
<position name="left_hip_pitch" joint="left_hip_pitch" ctrlrange="-3.14 2.53" class="hip" />
|
| 427 |
+
<position name="left_knee" joint="left_knee" ctrlrange="-0.26 2.05" class="knee" />
|
| 428 |
+
<position name="left_ankle" joint="left_ankle" ctrlrange="-0.87 0.52" class="ankle" />
|
| 429 |
+
<position name="right_hip_yaw" joint="right_hip_yaw" ctrlrange="-0.43 0.43" class="hip" />
|
| 430 |
+
<position name="right_hip_roll" joint="right_hip_roll" ctrlrange="-0.43 0.43" class="hip" />
|
| 431 |
+
<position name="right_hip_pitch" joint="right_hip_pitch" ctrlrange="-3.14 2.53" class="hip" />
|
| 432 |
+
<position name="right_knee" joint="right_knee" ctrlrange="-0.26 2.05" class="knee" />
|
| 433 |
+
<position name="right_ankle" joint="right_ankle" ctrlrange="-0.87 0.52" class="ankle" />
|
| 434 |
+
<position name="torso" joint="torso" ctrlrange="-2.35 2.35" class="torso" />
|
| 435 |
+
<position name="left_shoulder_pitch" joint="left_shoulder_pitch" ctrlrange="-2.87 2.87" class="shoulder1" />
|
| 436 |
+
<position name="left_shoulder_roll" joint="left_shoulder_roll" ctrlrange="-0.34 3.11" class="shoulder1" />
|
| 437 |
+
<position name="left_shoulder_yaw" joint="left_shoulder_yaw" ctrlrange="-1.3 4.45" class="shoulder2" />
|
| 438 |
+
<position name="left_elbow" joint="left_elbow" ctrlrange="-1.25 2.61" class="elbow" />
|
| 439 |
+
<position class="h1" name="left_hand" joint="left_hand" ctrlrange="-6 6"/>
|
| 440 |
+
<position name="right_shoulder_pitch" joint="right_shoulder_pitch" ctrlrange="-2.87 2.87" class="shoulder1" />
|
| 441 |
+
<position name="right_shoulder_roll" joint="right_shoulder_roll" ctrlrange="-3.11 0.34" class="shoulder1" />
|
| 442 |
+
<position name="right_shoulder_yaw" joint="right_shoulder_yaw" ctrlrange="-4.45 1.3" class="shoulder2" />
|
| 443 |
+
<position name="right_elbow" joint="right_elbow" ctrlrange="-1.25 2.61" class="elbow" />
|
| 444 |
+
<position class="h1" name="right_hand" joint="right_hand" ctrlrange="-6 6"/>
|
| 445 |
+
|
| 446 |
+
<position class="h1" name="L_index_proximal" joint="L_index_proximal" ctrlrange="-1 1"/>
|
| 447 |
+
<position class="h1" name="L_index_intermediate" joint="L_index_intermediate" ctrlrange="-1 1"/>
|
| 448 |
+
<position class="h1" name="L_middle_proximal" joint="L_middle_proximal" ctrlrange="-1 1"/>
|
| 449 |
+
<position class="h1" name="L_middle_intermediate" joint="L_middle_intermediate" ctrlrange="-1 1"/>
|
| 450 |
+
<position class="h1" name="L_ring_proximal" joint="L_ring_proximal" ctrlrange="-1 1"/>
|
| 451 |
+
<position class="h1" name="L_ring_intermediate" joint="L_ring_intermediate" ctrlrange="-1 1"/>
|
| 452 |
+
<position class="h1" name="L_pinky_proximal" joint="L_pinky_proximal" ctrlrange="-1 1"/>
|
| 453 |
+
<position class="h1" name="L_pinky_intermediate" joint="L_pinky_intermediate" ctrlrange="-1 1"/>
|
| 454 |
+
<position class="h1" name="L_thumb_proximal_yaw" joint="L_thumb_proximal_yaw" ctrlrange="-1 1"/>
|
| 455 |
+
<position class="h1" name="L_thumb_proximal_pitch" joint="L_thumb_proximal_pitch" ctrlrange="-1 1"/>
|
| 456 |
+
<position class="h1" name="L_thumb_intermediate" joint="L_thumb_intermediate" ctrlrange="-1 1"/>
|
| 457 |
+
<position class="h1" name="L_thumb_distal" joint="L_thumb_distal" ctrlrange="-1 1"/>
|
| 458 |
+
|
| 459 |
+
<position class="h1" name="R_index_proximal" joint="R_index_proximal" ctrlrange="-1 1"/>
|
| 460 |
+
<position class="h1" name="R_index_intermediate" joint="R_index_intermediate" ctrlrange="-1 1"/>
|
| 461 |
+
<position class="h1" name="R_middle_proximal" joint="R_middle_proximal" ctrlrange="-1 1"/>
|
| 462 |
+
<position class="h1" name="R_middle_intermediate" joint="R_middle_intermediate" ctrlrange="-1 1"/>
|
| 463 |
+
<position class="h1" name="R_ring_proximal" joint="R_ring_proximal" ctrlrange="-1 1"/>
|
| 464 |
+
<position class="h1" name="R_ring_intermediate" joint="R_ring_intermediate" ctrlrange="-1 1"/>
|
| 465 |
+
<position class="h1" name="R_pinky_proximal" joint="R_pinky_proximal" ctrlrange="-1 1"/>
|
| 466 |
+
<position class="h1" name="R_pinky_intermediate" joint="R_pinky_intermediate" ctrlrange="-1 1"/>
|
| 467 |
+
<position class="h1" name="R_thumb_proximal_yaw" joint="R_thumb_proximal_yaw" ctrlrange="-1 1"/>
|
| 468 |
+
<position class="h1" name="R_thumb_proximal_pitch" joint="R_thumb_proximal_pitch" ctrlrange="-1 1"/>
|
| 469 |
+
<position class="h1" name="R_thumb_intermediate" joint="R_thumb_intermediate" ctrlrange="-1 1"/>
|
| 470 |
+
<position class="h1" name="R_thumb_distal" joint="R_thumb_distal" ctrlrange="-1 1"/>
|
| 471 |
+
</actuator>
|
| 472 |
+
|
| 473 |
+
<sensor>
|
| 474 |
+
<touch name="left_foot_sensor" site="left_foot"/>
|
| 475 |
+
<touch name="right_foot_sensor" site="right_foot"/>
|
| 476 |
+
<subtreelinvel name="pelvis_subtreelinvel" body="pelvis"/>
|
| 477 |
+
<subtreelinvel name="left_hand_subtreelinvel" body="left_hand_link"/>
|
| 478 |
+
<subtreelinvel name="right_hand_subtreelinvel" body="right_hand_link"/>
|
| 479 |
+
<velocimeter name="body_velocimeter" site="com"/>
|
| 480 |
+
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
| 481 |
+
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
| 482 |
+
</sensor>
|
| 483 |
+
</mujoco>
|