Add humanoid asset.
Browse files- humanoid.xml +313 -0
humanoid.xml
ADDED
|
@@ -0,0 +1,313 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
<mujoco model="humanoid">
|
| 2 |
+
<option integrator="implicitfast"/>
|
| 3 |
+
<visual>
|
| 4 |
+
<global offwidth="1280" offheight="960"/>
|
| 5 |
+
<headlight active="1" ambient="0.34 0.34 0.34" diffuse="0.5 0.5 0.5"/>
|
| 6 |
+
</visual>
|
| 7 |
+
<default>
|
| 8 |
+
<joint damping="2" stiffness="2" armature="0.01" limited="true" solimplimit="0 .99 .01"/>
|
| 9 |
+
<geom condim="1" friction="0.7 0.005 0.0001" solimp=".99 .99 .003" solref="0.015 1" margin="0.001" rgba="0.8 0.6 .4 1"/>
|
| 10 |
+
<default class="smplcontact">
|
| 11 |
+
<geom condim="3" friction="1. 0.005 0.0001" solref="0.015 1" solimp="0.98 0.98 0.001" priority="1"/>
|
| 12 |
+
</default>
|
| 13 |
+
<default class="stiff_medium">
|
| 14 |
+
<joint stiffness="10"/>
|
| 15 |
+
</default>
|
| 16 |
+
<default class="stiff_medium_higher">
|
| 17 |
+
<joint stiffness="50"/>
|
| 18 |
+
</default>
|
| 19 |
+
<default class="stiff_high">
|
| 20 |
+
<joint stiffness="100"/>
|
| 21 |
+
</default>
|
| 22 |
+
</default>
|
| 23 |
+
<asset>
|
| 24 |
+
<texture type="skybox" builtin="gradient" rgb1="0.99 0.99 0.99" rgb2="0.608 0.828 0.892" width="100"/>
|
| 25 |
+
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/>
|
| 26 |
+
<material name="geom" texture="texgeom" texuniform="true"/>
|
| 27 |
+
</asset>
|
| 28 |
+
<worldbody>
|
| 29 |
+
<light name="tracking_light" pos="0 0 7" dir="0 0 -1" directional="true" cutoff="100" exponent="1" diffuse="1 1 1" specular="0.1 0.1 0.1" mode="trackcom"/>
|
| 30 |
+
<camera name="back" pos="0 3 2.4" xyaxes="-1 0 0 0 -1 2" mode="trackcom"/>
|
| 31 |
+
<camera name="side" pos="-3 0 2.4" xyaxes="0 -1 0 1 0 2" mode="trackcom"/>
|
| 32 |
+
<camera name="front_side" pos="-2.8 -2.8 0.8" xyaxes="0.5 -0.5 0 0.1 0.1 1" mode="trackcom"/>
|
| 33 |
+
<body name="Pelvis" pos="-0.0018 -0.2233 0.0282">
|
| 34 |
+
<site name="Pelvis" size="0.01"/>
|
| 35 |
+
<freejoint name="Pelvis"/>
|
| 36 |
+
<geom type="box" pos="-0.0000 -0.0121 -0.0055" size="0.1069 0.0722 0.083" quat="1.0000 0.0000 0.0000 0.0000" density="3165.830099" name="Pelvis"/>
|
| 37 |
+
<body name="L_Hip" pos="0.0695 -0.0914 -0.0068">
|
| 38 |
+
<joint name="L_Hip_x" type="hinge" pos="0 0 0" axis="1 0 0" stiffness="10" range="-160.0 22.92" class="stiff_medium" damping="15"/>
|
| 39 |
+
<joint name="L_Hip_y" type="hinge" pos="0 0 0" axis="0 1 0" stiffness="10" range="-70.0 70.0" class="stiff_medium" damping="10"/>
|
| 40 |
+
<joint name="L_Hip_z" type="hinge" pos="0 0 0" axis="0 0 1" stiffness="10" range="-28.65 90.0" class="stiff_medium" damping="10"/>
|
| 41 |
+
<geom type="capsule" density="2040.816327" fromto="0.0069 -0.0750 -0.0009 0.0274 -0.3002 -0.0036" size="0.0615" name="L_Hip"/>
|
| 42 |
+
<body name="L_Knee" pos="0.0343 -0.3752 -0.0045">
|
| 43 |
+
<joint name="L_Knee_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-5.16 171.89" damping="8"/>
|
| 44 |
+
<joint name="L_Knee_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-4.58 6.88" damping="8"/>
|
| 45 |
+
<joint name="L_Knee_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-6.88 4.58" damping="8"/>
|
| 46 |
+
<geom type="capsule" density="1234.567901" fromto="-0.0027 -0.0796 -0.0087 -0.0109 -0.3184 -0.0350" size="0.0541" name="L_Knee"/>
|
| 47 |
+
<body name="L_Ankle" pos="-0.0136 -0.398 -0.0437">
|
| 48 |
+
<joint name="L_Ankle_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-45.84 45.84" class="stiff_medium" damping="6"/>
|
| 49 |
+
<joint name="L_Ankle_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-74.48 22.92" class="stiff_medium" damping="3"/>
|
| 50 |
+
<joint name="L_Ankle_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-4.58 4.58" class="stiff_medium" damping="6"/>
|
| 51 |
+
<geom type="box" pos="0.0233 -0.0239 0.0242" size="0.0483 0.0464 0.085" quat="1.0000 0.0000 0.0000 0.0000" density="449.071558" name="L_Ankle" class="smplcontact"/>
|
| 52 |
+
<body name="L_Toe" pos="0.0264 -0.0558 0.1193">
|
| 53 |
+
<joint name="L_Toe_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-91.67 22.92"/>
|
| 54 |
+
<joint name="L_Toe_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-4.58 4.58"/>
|
| 55 |
+
<joint name="L_Toe_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-4.58 4.58"/>
|
| 56 |
+
<geom type="box" pos="-0.0030 0.0055 0.0248" size="0.0478 0.02 0.0496" quat="1.0000 0.0000 0.0000 0.0000" density="423.206892" name="L_Toe" class="smplcontact"/>
|
| 57 |
+
</body>
|
| 58 |
+
</body>
|
| 59 |
+
</body>
|
| 60 |
+
</body>
|
| 61 |
+
<body name="R_Hip" pos="-0.0677 -0.0905 -0.0043">
|
| 62 |
+
<joint name="R_Hip_x" type="hinge" pos="0 0 0" axis="1 0 0" stiffness="10" range="-160.0 22.92" class="stiff_medium" damping="15"/>
|
| 63 |
+
<joint name="R_Hip_y" type="hinge" pos="0 0 0" axis="0 1 0" stiffness="10" range="-70.0 70.0" class="stiff_medium" damping="10"/>
|
| 64 |
+
<joint name="R_Hip_z" type="hinge" pos="0 0 0" axis="0 0 1" stiffness="10" range="-90.0 28.65" class="stiff_medium" damping="10"/>
|
| 65 |
+
<geom type="capsule" density="2040.816327" fromto="-0.0077 -0.0765 -0.0018 -0.0306 -0.3061 -0.0071" size="0.0606" name="R_Hip"/>
|
| 66 |
+
<body name="R_Knee" pos="-0.0383 -0.3826 -0.0089">
|
| 67 |
+
<joint name="R_Knee_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-5.16 171.89" damping="8"/>
|
| 68 |
+
<joint name="R_Knee_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-6.88 4.58" damping="8"/>
|
| 69 |
+
<joint name="R_Knee_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-4.58 6.88" damping="8"/>
|
| 70 |
+
<geom type="capsule" density="1234.567901" fromto="0.0032 -0.0797 -0.0085 0.0126 -0.3187 -0.0338" size="0.0541" name="R_Knee"/>
|
| 71 |
+
<body name="R_Ankle" pos="0.0158 -0.3984 -0.0423">
|
| 72 |
+
<joint name="R_Ankle_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-45.84 45.84" class="stiff_medium" damping="6"/>
|
| 73 |
+
<joint name="R_Ankle_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-22.92 74.48" class="stiff_medium" damping="3"/>
|
| 74 |
+
<joint name="R_Ankle_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-4.58 4.58" class="stiff_medium" damping="6"/>
|
| 75 |
+
<geom type="box" pos="-0.0212 -0.0174 0.0256" size="0.0483 0.0478 0.0865" quat="1.0000 0.0000 0.0000 0.0000" density="434.700981" name="R_Ankle" class="smplcontact"/>
|
| 76 |
+
<body name="R_Toe" pos="-0.0254 -0.0481 0.1233">
|
| 77 |
+
<joint name="R_Toe_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-91.67 22.92"/>
|
| 78 |
+
<joint name="R_Toe_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-4.58 4.58"/>
|
| 79 |
+
<joint name="R_Toe_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-4.58 4.58"/>
|
| 80 |
+
<geom type="box" pos="0.0042 0.0045 0.0227" size="0.0479 0.0216 0.0493" quat="1.0000 0.0000 0.0000 0.0000" density="407.384095" name="R_Toe" class="smplcontact"/>
|
| 81 |
+
</body>
|
| 82 |
+
</body>
|
| 83 |
+
</body>
|
| 84 |
+
</body>
|
| 85 |
+
<body name="Torso" pos="-0.0025 0.109 -0.0267">
|
| 86 |
+
<joint name="Torso_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-25.78 57.3" class="stiff_medium" damping="15"/>
|
| 87 |
+
<joint name="Torso_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-57.3 57.3" class="stiff_high" damping="20"/>
|
| 88 |
+
<joint name="Torso_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-34.38 34.38" class="stiff_high" damping="20"/>
|
| 89 |
+
<geom type="capsule" density="2040.816327" fromto="0.0025 0.0608 0.0005 0.0030 0.0743 0.0006" size="0.0769" name="Torso"/>
|
| 90 |
+
<body name="Spine" pos="0.0055 0.1352 0.0011">
|
| 91 |
+
<joint name="Spine_x" type="hinge" pos="0 0 0" axis="1 0 0" stiffness="10" range="-25.78 57.3" class="stiff_medium" damping="15"/>
|
| 92 |
+
<joint name="Spine_y" type="hinge" pos="0 0 0" axis="0 1 0" stiffness="10" range="-57.3 57.3" class="stiff_high" damping="8"/>
|
| 93 |
+
<joint name="Spine_z" type="hinge" pos="0 0 0" axis="0 0 1" stiffness="20" range="-34.38 34.38" class="stiff_high" damping="12"/>
|
| 94 |
+
<geom type="capsule" density="2040.816327" fromto="0.0007 0.0238 0.0114 0.0008 0.0291 0.0140" size="0.0755" name="Spine"/>
|
| 95 |
+
<body name="Chest" pos="0.0015 0.0529 0.0254">
|
| 96 |
+
<joint name="Chest_x" type="hinge" pos="0 0 0" axis="1 0 0" stiffness="10" range="-25.78 57.3" class="stiff_medium" damping="15"/>
|
| 97 |
+
<joint name="Chest_y" type="hinge" pos="0 0 0" axis="0 1 0" stiffness="10" range="-57.3 57.3" class="stiff_high" damping="8"/>
|
| 98 |
+
<joint name="Chest_z" type="hinge" pos="0 0 0" axis="0 0 1" stiffness="20" range="-34.38 34.38" class="stiff_high" damping="12"/>
|
| 99 |
+
<geom type="capsule" density="2040.816327" fromto="-0.0009 0.0682 -0.0173 -0.0010 0.0833 -0.0212" size="0.1002" name="Chest"/>
|
| 100 |
+
<body name="Neck" pos="-0.0028 0.2139 -0.0429">
|
| 101 |
+
<joint name="Neck_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-28.65 57.3" class="stiff_medium_higher" damping="10"/>
|
| 102 |
+
<joint name="Neck_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-40.11 40.11" class="stiff_medium_higher" damping="10"/>
|
| 103 |
+
<joint name="Neck_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-40.11 40.11" class="stiff_medium_higher" damping="10"/>
|
| 104 |
+
<geom type="capsule" density="1000" fromto="0.0010 0.0130 0.0103 0.0041 0.0520 0.0411" size="0.0436" name="Neck"/>
|
| 105 |
+
<body name="Head" pos="0.0052 0.065 0.0513">
|
| 106 |
+
<joint name="Head_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-28.65 57.3" class="stiff_medium_higher" damping="2"/>
|
| 107 |
+
<joint name="Head_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-40.11 40.11" class="stiff_medium_higher" damping="2"/>
|
| 108 |
+
<joint name="Head_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-40.11 40.11" class="stiff_medium_higher" damping="2"/>
|
| 109 |
+
<geom type="box" pos="-0.0042 0.0876 -0.0116" size="0.0606 0.1154 0.076" quat="1.0000 0.0000 0.0000 0.0000" density="1018.069894" name="Head"/>
|
| 110 |
+
<geom type="capsule" name="nose" size="0.02 0.01" pos="0 0.07 .05" quat="1 0 0 0" mass="0" contype="0" conaffinity="0"/>
|
| 111 |
+
</body>
|
| 112 |
+
</body>
|
| 113 |
+
<body name="L_Thorax" pos="0.0788 0.1217 -0.0341">
|
| 114 |
+
<joint name="L_Thorax_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-10.89 4.58" class="stiff_medium_higher" damping="20"/>
|
| 115 |
+
<joint name="L_Thorax_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-28.65 17.19" class="stiff_medium_higher" damping="20"/>
|
| 116 |
+
<joint name="L_Thorax_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-31.51 40.11" class="stiff_medium_higher" damping="20"/>
|
| 117 |
+
<geom type="capsule" density="1000" fromto="0.0182 0.0061 -0.0018 0.0728 0.0244 -0.0071" size="0.0521" name="L_Thorax"/>
|
| 118 |
+
<body name="L_Shoulder" pos="0.091 0.0305 -0.0089">
|
| 119 |
+
<joint name="L_Shoulder_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-97.4 97.4" class="stiff_medium" damping="6"/>
|
| 120 |
+
<joint name="L_Shoulder_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-108.86 80.21" class="stiff_medium" damping="6"/>
|
| 121 |
+
<joint name="L_Shoulder_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-97.4 85.94" class="stiff_medium" damping="6"/>
|
| 122 |
+
<geom type="capsule" density="1000" fromto="0.0519 -0.0026 -0.0055 0.2077 -0.0102 -0.0220" size="0.0517" name="L_Shoulder"/>
|
| 123 |
+
<body name="L_Elbow" pos="0.2596 -0.0128 -0.0275">
|
| 124 |
+
<joint name="L_Elbow_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-17.19 4.58" damping="5"/>
|
| 125 |
+
<joint name="L_Elbow_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-180.0 17.19" damping="5"/>
|
| 126 |
+
<joint name="L_Elbow_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-100.84 4.58" damping="5"/>
|
| 127 |
+
<geom type="capsule" density="1000" fromto="0.0498 0.0018 -0.0002 0.1994 0.0072 -0.0009" size="0.0405" name="L_Elbow"/>
|
| 128 |
+
<body name="L_Wrist" pos="0.2492 0.009 -0.0012">
|
| 129 |
+
<joint name="L_Wrist_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-180.0 22.92"/>
|
| 130 |
+
<joint name="L_Wrist_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-17.19 17.19"/>
|
| 131 |
+
<joint name="L_Wrist_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-22.92 22.92"/>
|
| 132 |
+
<geom type="capsule" density="1000" fromto="0.0168 -0.0016 -0.0030 0.0672 -0.0065 -0.0120" size="0.0318" name="L_Wrist" class="smplcontact"/>
|
| 133 |
+
<body name="L_Hand" pos="0.084 -0.0082 -0.0149">
|
| 134 |
+
<joint name="L_Hand_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-17.19 17.19"/>
|
| 135 |
+
<joint name="L_Hand_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-51.57 51.57"/>
|
| 136 |
+
<joint name="L_Hand_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-91.67 91.67"/>
|
| 137 |
+
<geom type="box" pos="0.0493 0.0010 -0.0058" size="0.0585 0.0158 0.0538" quat="1.0000 0.0000 0.0000 0.0000" density="400.552564" name="L_Hand" class="smplcontact"/>
|
| 138 |
+
</body>
|
| 139 |
+
</body>
|
| 140 |
+
</body>
|
| 141 |
+
</body>
|
| 142 |
+
</body>
|
| 143 |
+
<body name="R_Thorax" pos="-0.0818 0.1188 -0.0386">
|
| 144 |
+
<joint name="R_Thorax_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-10.89 4.58" class="stiff_medium_higher" damping="20"/>
|
| 145 |
+
<joint name="R_Thorax_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-17.19 28.65" class="stiff_medium_higher" damping="20"/>
|
| 146 |
+
<joint name="R_Thorax_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-40.11 31.51" class="stiff_medium_higher" damping="20"/>
|
| 147 |
+
<geom type="capsule" density="1000" fromto="-0.0192 0.0065 -0.0018 -0.0768 0.0260 -0.0073" size="0.0511" name="R_Thorax"/>
|
| 148 |
+
<body name="R_Shoulder" pos="-0.096 0.0326 -0.0091">
|
| 149 |
+
<joint name="R_Shoulder_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-97.4 97.4" class="stiff_medium" damping="6"/>
|
| 150 |
+
<joint name="R_Shoulder_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-80.21 108.86" class="stiff_medium" damping="6"/>
|
| 151 |
+
<joint name="R_Shoulder_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-85.94 97.4" class="stiff_medium" damping="6"/>
|
| 152 |
+
<geom type="capsule" density="1000" fromto="-0.0507 -0.0027 -0.0043 -0.2030 -0.0107 -0.0171" size="0.0531" name="R_Shoulder"/>
|
| 153 |
+
<body name="R_Elbow" pos="-0.2537 -0.0133 -0.0214">
|
| 154 |
+
<joint name="R_Elbow_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-17.19 4.58" damping="5"/>
|
| 155 |
+
<joint name="R_Elbow_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-17.19 180.0" damping="5"/>
|
| 156 |
+
<joint name="R_Elbow_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-4.58 100.84" damping="5"/>
|
| 157 |
+
<geom type="capsule" density="1000" fromto="-0.0511 0.0016 -0.0011 -0.2042 0.0062 -0.0044" size="0.0408" name="R_Elbow"/>
|
| 158 |
+
<body name="R_Wrist" pos="-0.2553 0.0078 -0.0056">
|
| 159 |
+
<joint name="R_Wrist_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-180.0 22.92"/>
|
| 160 |
+
<joint name="R_Wrist_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-17.19 17.19"/>
|
| 161 |
+
<joint name="R_Wrist_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-22.92 22.92"/>
|
| 162 |
+
<geom type="capsule" density="1000" fromto="-0.0169 -0.0012 -0.0021 -0.0677 -0.0049 -0.0083" size="0.0326" name="R_Wrist" class="smplcontact"/>
|
| 163 |
+
<body name="R_Hand" pos="-0.0846 -0.0061 -0.0103">
|
| 164 |
+
<joint name="R_Hand_x" type="hinge" pos="0 0 0" axis="1 0 0" range="-17.19 17.19"/>
|
| 165 |
+
<joint name="R_Hand_y" type="hinge" pos="0 0 0" axis="0 1 0" range="-51.57 51.57"/>
|
| 166 |
+
<joint name="R_Hand_z" type="hinge" pos="0 0 0" axis="0 0 1" range="-91.67 91.67"/>
|
| 167 |
+
<geom type="box" pos="-0.0462 -0.0009 -0.0079" size="0.0569 0.0164 0.0546" quat="1.0000 0.0000 0.0000 0.0000" density="403.679611" name="R_Hand" class="smplcontact"/>
|
| 168 |
+
</body>
|
| 169 |
+
</body>
|
| 170 |
+
</body>
|
| 171 |
+
</body>
|
| 172 |
+
</body>
|
| 173 |
+
</body>
|
| 174 |
+
</body>
|
| 175 |
+
</body>
|
| 176 |
+
</body>
|
| 177 |
+
</worldbody>
|
| 178 |
+
<actuator>
|
| 179 |
+
<general name="L_Hip_x" joint="L_Hip_x" biastype="affine" gainprm="287.33006409732246" biasprm="-215.3247604770444 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 180 |
+
<general name="L_Hip_y" joint="L_Hip_y" biastype="affine" gainprm="219.9114857512855" biasprm="0.0 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 181 |
+
<general name="L_Hip_z" joint="L_Hip_z" biastype="affine" gainprm="186.3749841742145" biasprm="96.3683546488669 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 182 |
+
<general name="L_Knee_x" joint="L_Knee_x" biastype="affine" gainprm="278.10948965903646" biasprm="261.8988715665131 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 183 |
+
<general name="L_Knee_y" joint="L_Knee_y" biastype="affine" gainprm="18.001325905069514" biasprm="3.612831551628262 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 184 |
+
<general name="L_Knee_z" joint="L_Knee_z" biastype="affine" gainprm="18.001325905069514" biasprm="-3.612831551628262 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 185 |
+
<general name="L_Ankle_x" joint="L_Ankle_x" biastype="affine" gainprm="72.00530362027807" biasprm="0.0 -90 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-180 180"/>
|
| 186 |
+
<general name="L_Ankle_y" joint="L_Ankle_y" biastype="affine" gainprm="76.49778111491148" biasprm="-40.49512930477244 -90 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-180 180"/>
|
| 187 |
+
<general name="L_Ankle_z" joint="L_Ankle_z" biastype="affine" gainprm="7.1942471767206255" biasprm="0.0 -90 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-180 180"/>
|
| 188 |
+
<general name="L_Toe_x" joint="L_Toe_x" biastype="affine" gainprm="71.99902043497087" biasprm="-43.19689898685965 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 189 |
+
<general name="L_Toe_y" joint="L_Toe_y" biastype="affine" gainprm="5.755397741376501" biasprm="0.0 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 190 |
+
<general name="L_Toe_z" joint="L_Toe_z" biastype="affine" gainprm="5.755397741376501" biasprm="0.0 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 191 |
+
<general name="R_Hip_x" joint="R_Hip_x" biastype="affine" gainprm="287.33006409732246" biasprm="-215.3247604770444 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 192 |
+
<general name="R_Hip_y" joint="R_Hip_y" biastype="affine" gainprm="219.9114857512855" biasprm="0.0 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 193 |
+
<general name="R_Hip_z" joint="R_Hip_z" biastype="affine" gainprm="186.3749841742145" biasprm="-96.3683546488669 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 194 |
+
<general name="R_Knee_x" joint="R_Knee_x" biastype="affine" gainprm="278.10948965903646" biasprm="261.8988715665131 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 195 |
+
<general name="R_Knee_y" joint="R_Knee_y" biastype="affine" gainprm="18.001325905069514" biasprm="-3.612831551628262 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 196 |
+
<general name="R_Knee_z" joint="R_Knee_z" biastype="affine" gainprm="18.001325905069514" biasprm="3.612831551628262 -180 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 197 |
+
<general name="R_Ankle_x" joint="R_Ankle_x" biastype="affine" gainprm="72.00530362027807" biasprm="0.0 -90 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-180 180"/>
|
| 198 |
+
<general name="R_Ankle_y" joint="R_Ankle_y" biastype="affine" gainprm="76.49778111491148" biasprm="40.49512930477244 -90 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-180 180"/>
|
| 199 |
+
<general name="R_Ankle_z" joint="R_Ankle_z" biastype="affine" gainprm="7.1942471767206255" biasprm="0.0 -90 -2.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-180 180"/>
|
| 200 |
+
<general name="R_Toe_x" joint="R_Toe_x" biastype="affine" gainprm="71.99902043497087" biasprm="-43.19689898685965 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 201 |
+
<general name="R_Toe_y" joint="R_Toe_y" biastype="affine" gainprm="5.755397741376501" biasprm="0.0 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 202 |
+
<general name="R_Toe_z" joint="R_Toe_z" biastype="affine" gainprm="5.755397741376501" biasprm="0.0 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 203 |
+
<general name="Torso_x" joint="Torso_x" biastype="affine" gainprm="174.00234510682668" biasprm="66.0153336274335 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 204 |
+
<general name="Torso_y" joint="Torso_y" biastype="affine" gainprm="240.0176787342602" biasprm="0.0 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 205 |
+
<general name="Torso_z" joint="Torso_z" biastype="affine" gainprm="144.01060724055614" biasprm="0.0 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 206 |
+
<general name="Spine_x" joint="Spine_x" biastype="affine" gainprm="174.00234510682668" biasprm="66.0153336274335 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 207 |
+
<general name="Spine_y" joint="Spine_y" biastype="affine" gainprm="240.0176787342602" biasprm="0.0 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 208 |
+
<general name="Spine_z" joint="Spine_z" biastype="affine" gainprm="144.01060724055614" biasprm="0.0 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 209 |
+
<general name="Chest_x" joint="Chest_x" biastype="affine" gainprm="174.00234510682668" biasprm="66.0153336274335 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 210 |
+
<general name="Chest_y" joint="Chest_y" biastype="affine" gainprm="240.0176787342602" biasprm="0.0 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 211 |
+
<general name="Chest_z" joint="Chest_z" biastype="affine" gainprm="144.01060724055614" biasprm="0.0 -240 -4.0" ctrllimited="true" ctrlrange="-1 1" forcerange="-360 360"/>
|
| 212 |
+
<general name="Neck_x" joint="Neck_x" biastype="affine" gainprm="27.00198885760427" biasprm="9.000662952534757 -36 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-72 72"/>
|
| 213 |
+
<general name="Neck_y" joint="Neck_y" biastype="affine" gainprm="25.20185626709732" biasprm="0.0 -36 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-72 72"/>
|
| 214 |
+
<general name="Neck_z" joint="Neck_z" biastype="affine" gainprm="25.20185626709732" biasprm="0.0 -36 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-72 72"/>
|
| 215 |
+
<general name="Head_x" joint="Head_x" biastype="affine" gainprm="18.001325905069514" biasprm="6.000441968356505 -24 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-48 48"/>
|
| 216 |
+
<general name="Head_y" joint="Head_y" biastype="affine" gainprm="16.801237511398213" biasprm="0.0 -24 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-48 48"/>
|
| 217 |
+
<general name="Head_z" joint="Head_z" biastype="affine" gainprm="16.801237511398213" biasprm="0.0 -24 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-48 48"/>
|
| 218 |
+
<general name="L_Thorax_x" joint="L_Thorax_x" biastype="affine" gainprm="16.200146117011364" biasprm="-6.6078165480505335 -120 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-240 240"/>
|
| 219 |
+
<general name="L_Thorax_y" joint="L_Thorax_y" biastype="affine" gainprm="48.00353574685204" biasprm="-12.00088393671301 -120 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-240 240"/>
|
| 220 |
+
<general name="L_Thorax_z" joint="L_Thorax_z" biastype="affine" gainprm="75.00028861670033" biasprm="9.00589894029074 -120 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-240 240"/>
|
| 221 |
+
<general name="L_Shoulder_x" joint="L_Shoulder_x" biastype="affine" gainprm="81.5976331892389" biasprm="0.0 -48 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-96 96"/>
|
| 222 |
+
<general name="L_Shoulder_y" joint="L_Shoulder_y" biastype="affine" gainprm="79.19745640189629" biasprm="-12.00088393671301 -48 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-96 96"/>
|
| 223 |
+
<general name="L_Shoulder_z" joint="L_Shoulder_z" biastype="affine" gainprm="76.79727961455369" biasprm="-4.800353574685214 -48 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-96 96"/>
|
| 224 |
+
<general name="L_Elbow_x" joint="L_Elbow_x" biastype="affine" gainprm="13.67849441372996" biasprm="-7.923096672353461 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 225 |
+
<general name="L_Elbow_y" joint="L_Elbow_y" biastype="affine" gainprm="123.89813107227425" biasprm="-102.29653998619085 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 226 |
+
<general name="L_Elbow_z" joint="L_Elbow_z" biastype="affine" gainprm="66.23733950828719" biasprm="-60.4819417669107 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 227 |
+
<general name="L_Wrist_x" joint="L_Wrist_x" biastype="affine" gainprm="21.24973270888136" biasprm="-16.449379134196157 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 228 |
+
<general name="L_Wrist_y" joint="L_Wrist_y" biastype="affine" gainprm="3.6002651810139037" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 229 |
+
<general name="L_Wrist_z" joint="L_Wrist_z" biastype="affine" gainprm="4.800353574685205" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 230 |
+
<general name="L_Hand_x" joint="L_Hand_x" biastype="affine" gainprm="3.6002651810139037" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 231 |
+
<general name="L_Hand_y" joint="L_Hand_y" biastype="affine" gainprm="10.800795543041708" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 232 |
+
<general name="L_Hand_z" joint="L_Hand_z" biastype="affine" gainprm="19.199319903638422" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 233 |
+
<general name="R_Thorax_x" joint="R_Thorax_x" biastype="affine" gainprm="16.200146117011364" biasprm="-6.6078165480505335 -120 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-240 240"/>
|
| 234 |
+
<general name="R_Thorax_y" joint="R_Thorax_y" biastype="affine" gainprm="48.00353574685204" biasprm="12.000883936713002 -120 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-240 240"/>
|
| 235 |
+
<general name="R_Thorax_z" joint="R_Thorax_z" biastype="affine" gainprm="75.00028861670033" biasprm="-9.00589894029074 -120 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-240 240"/>
|
| 236 |
+
<general name="R_Shoulder_x" joint="R_Shoulder_x" biastype="affine" gainprm="81.5976331892389" biasprm="0.0 -48 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-96 96"/>
|
| 237 |
+
<general name="R_Shoulder_y" joint="R_Shoulder_y" biastype="affine" gainprm="79.19745640189629" biasprm="12.00088393671301 -48 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-96 96"/>
|
| 238 |
+
<general name="R_Shoulder_z" joint="R_Shoulder_z" biastype="affine" gainprm="76.79727961455369" biasprm="4.800353574685204 -48 -1.6" ctrllimited="true" ctrlrange="-1 1" forcerange="-96 96"/>
|
| 239 |
+
<general name="R_Elbow_x" joint="R_Elbow_x" biastype="affine" gainprm="13.67849441372996" biasprm="-7.923096672353461 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 240 |
+
<general name="R_Elbow_y" joint="R_Elbow_y" biastype="affine" gainprm="123.89813107227425" biasprm="102.29653998619085 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 241 |
+
<general name="R_Elbow_z" joint="R_Elbow_z" biastype="affine" gainprm="66.23733950828719" biasprm="60.481941766910694 -72 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-144 144"/>
|
| 242 |
+
<general name="R_Wrist_x" joint="R_Wrist_x" biastype="affine" gainprm="21.24973270888136" biasprm="-16.449379134196157 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 243 |
+
<general name="R_Wrist_y" joint="R_Wrist_y" biastype="affine" gainprm="3.6002651810139037" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 244 |
+
<general name="R_Wrist_z" joint="R_Wrist_z" biastype="affine" gainprm="4.800353574685205" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 245 |
+
<general name="R_Hand_x" joint="R_Hand_x" biastype="affine" gainprm="3.6002651810139037" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 246 |
+
<general name="R_Hand_y" joint="R_Hand_y" biastype="affine" gainprm="10.800795543041708" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 247 |
+
<general name="R_Hand_z" joint="R_Hand_z" biastype="affine" gainprm="19.199319903638422" biasprm="0.0 -12 -0.8" ctrllimited="true" ctrlrange="-1 1" forcerange="-24 24"/>
|
| 248 |
+
</actuator>
|
| 249 |
+
<contact>
|
| 250 |
+
<exclude body1="Torso" body2="Chest"/>
|
| 251 |
+
<exclude body1="Head" body2="Chest"/>
|
| 252 |
+
<exclude body1="R_Knee" body2="R_Toe"/>
|
| 253 |
+
<exclude body1="R_Knee" body2="L_Ankle"/>
|
| 254 |
+
<exclude body1="R_Knee" body2="L_Toe"/>
|
| 255 |
+
<exclude body1="L_Knee" body2="L_Toe"/>
|
| 256 |
+
<exclude body1="L_Knee" body2="R_Ankle"/>
|
| 257 |
+
<exclude body1="L_Knee" body2="R_Toe"/>
|
| 258 |
+
<exclude body1="L_Shoulder" body2="Chest"/>
|
| 259 |
+
<exclude body1="R_Shoulder" body2="Chest"/>
|
| 260 |
+
</contact>
|
| 261 |
+
<sensor>
|
| 262 |
+
<framelinvel name="sensor_Pelvis_framelinvel" objtype="xbody" objname="Pelvis"/>
|
| 263 |
+
<framelinvel name="sensor_L_Hip_framelinvel" objtype="xbody" objname="L_Hip"/>
|
| 264 |
+
<framelinvel name="sensor_L_Knee_framelinvel" objtype="xbody" objname="L_Knee"/>
|
| 265 |
+
<framelinvel name="sensor_L_Ankle_framelinvel" objtype="xbody" objname="L_Ankle"/>
|
| 266 |
+
<framelinvel name="sensor_L_Toe_framelinvel" objtype="xbody" objname="L_Toe"/>
|
| 267 |
+
<framelinvel name="sensor_R_Hip_framelinvel" objtype="xbody" objname="R_Hip"/>
|
| 268 |
+
<framelinvel name="sensor_R_Knee_framelinvel" objtype="xbody" objname="R_Knee"/>
|
| 269 |
+
<framelinvel name="sensor_R_Ankle_framelinvel" objtype="xbody" objname="R_Ankle"/>
|
| 270 |
+
<framelinvel name="sensor_R_Toe_framelinvel" objtype="xbody" objname="R_Toe"/>
|
| 271 |
+
<framelinvel name="sensor_Torso_framelinvel" objtype="xbody" objname="Torso"/>
|
| 272 |
+
<framelinvel name="sensor_Spine_framelinvel" objtype="xbody" objname="Spine"/>
|
| 273 |
+
<framelinvel name="sensor_Chest_framelinvel" objtype="xbody" objname="Chest"/>
|
| 274 |
+
<framelinvel name="sensor_Neck_framelinvel" objtype="xbody" objname="Neck"/>
|
| 275 |
+
<framelinvel name="sensor_Head_framelinvel" objtype="xbody" objname="Head"/>
|
| 276 |
+
<framelinvel name="sensor_L_Thorax_framelinvel" objtype="xbody" objname="L_Thorax"/>
|
| 277 |
+
<framelinvel name="sensor_L_Shoulder_framelinvel" objtype="xbody" objname="L_Shoulder"/>
|
| 278 |
+
<framelinvel name="sensor_L_Elbow_framelinvel" objtype="xbody" objname="L_Elbow"/>
|
| 279 |
+
<framelinvel name="sensor_L_Wrist_framelinvel" objtype="xbody" objname="L_Wrist"/>
|
| 280 |
+
<framelinvel name="sensor_L_Hand_framelinvel" objtype="xbody" objname="L_Hand"/>
|
| 281 |
+
<framelinvel name="sensor_R_Thorax_framelinvel" objtype="xbody" objname="R_Thorax"/>
|
| 282 |
+
<framelinvel name="sensor_R_Shoulder_framelinvel" objtype="xbody" objname="R_Shoulder"/>
|
| 283 |
+
<framelinvel name="sensor_R_Elbow_framelinvel" objtype="xbody" objname="R_Elbow"/>
|
| 284 |
+
<framelinvel name="sensor_R_Wrist_framelinvel" objtype="xbody" objname="R_Wrist"/>
|
| 285 |
+
<framelinvel name="sensor_R_Hand_framelinvel" objtype="xbody" objname="R_Hand"/>
|
| 286 |
+
<frameangvel name="sensor_Pelvis_frameangvel" objtype="xbody" objname="Pelvis"/>
|
| 287 |
+
<frameangvel name="sensor_L_Hip_frameangvel" objtype="xbody" objname="L_Hip"/>
|
| 288 |
+
<frameangvel name="sensor_L_Knee_frameangvel" objtype="xbody" objname="L_Knee"/>
|
| 289 |
+
<frameangvel name="sensor_L_Ankle_frameangvel" objtype="xbody" objname="L_Ankle"/>
|
| 290 |
+
<frameangvel name="sensor_L_Toe_frameangvel" objtype="xbody" objname="L_Toe"/>
|
| 291 |
+
<frameangvel name="sensor_R_Hip_frameangvel" objtype="xbody" objname="R_Hip"/>
|
| 292 |
+
<frameangvel name="sensor_R_Knee_frameangvel" objtype="xbody" objname="R_Knee"/>
|
| 293 |
+
<frameangvel name="sensor_R_Ankle_frameangvel" objtype="xbody" objname="R_Ankle"/>
|
| 294 |
+
<frameangvel name="sensor_R_Toe_frameangvel" objtype="xbody" objname="R_Toe"/>
|
| 295 |
+
<frameangvel name="sensor_Torso_frameangvel" objtype="xbody" objname="Torso"/>
|
| 296 |
+
<frameangvel name="sensor_Spine_frameangvel" objtype="xbody" objname="Spine"/>
|
| 297 |
+
<frameangvel name="sensor_Chest_frameangvel" objtype="xbody" objname="Chest"/>
|
| 298 |
+
<frameangvel name="sensor_Neck_frameangvel" objtype="xbody" objname="Neck"/>
|
| 299 |
+
<frameangvel name="sensor_Head_frameangvel" objtype="xbody" objname="Head"/>
|
| 300 |
+
<frameangvel name="sensor_L_Thorax_frameangvel" objtype="xbody" objname="L_Thorax"/>
|
| 301 |
+
<frameangvel name="sensor_L_Shoulder_frameangvel" objtype="xbody" objname="L_Shoulder"/>
|
| 302 |
+
<frameangvel name="sensor_L_Elbow_frameangvel" objtype="xbody" objname="L_Elbow"/>
|
| 303 |
+
<frameangvel name="sensor_L_Wrist_frameangvel" objtype="xbody" objname="L_Wrist"/>
|
| 304 |
+
<frameangvel name="sensor_L_Hand_frameangvel" objtype="xbody" objname="L_Hand"/>
|
| 305 |
+
<frameangvel name="sensor_R_Thorax_frameangvel" objtype="xbody" objname="R_Thorax"/>
|
| 306 |
+
<frameangvel name="sensor_R_Shoulder_frameangvel" objtype="xbody" objname="R_Shoulder"/>
|
| 307 |
+
<frameangvel name="sensor_R_Elbow_frameangvel" objtype="xbody" objname="R_Elbow"/>
|
| 308 |
+
<frameangvel name="sensor_R_Wrist_frameangvel" objtype="xbody" objname="R_Wrist"/>
|
| 309 |
+
<frameangvel name="sensor_R_Hand_frameangvel" objtype="xbody" objname="R_Hand"/>
|
| 310 |
+
<subtreelinvel name="Chest_subtreelinvel" body="Chest"/>
|
| 311 |
+
<gyro name="Pelvis_gyro" site="Pelvis"/>
|
| 312 |
+
</sensor>
|
| 313 |
+
</mujoco>
|