Update mujoco/booster_t1/booster_t1.xml
Browse files- mujoco/booster_t1/booster_t1.xml +73 -146
mujoco/booster_t1/booster_t1.xml
CHANGED
|
@@ -39,108 +39,39 @@
|
|
| 39 |
|
| 40 |
<default>
|
| 41 |
<default class="t1">
|
| 42 |
-
<geom
|
| 43 |
<site rgba="1 0 0 1" size="0.01" group="5"/>
|
|
|
|
|
|
|
| 44 |
<default class="visual">
|
| 45 |
-
<geom type="mesh" contype="0" conaffinity="0" group="
|
| 46 |
</default>
|
| 47 |
<default class="collision">
|
| 48 |
<geom group="3"/>
|
| 49 |
-
<default class="foot">
|
| 50 |
-
<geom size="0.1115 0.05 0.015" pos="0.01 0 -0.015" type="box" contype="4" conaffinity="4"/>
|
| 51 |
-
<default class="foot_sphere">
|
| 52 |
-
<geom contype="2" conaffinity="1" size=".01" type="sphere"/>
|
| 53 |
-
</default>
|
| 54 |
-
</default>
|
| 55 |
-
</default>
|
| 56 |
-
|
| 57 |
-
<joint frictionloss="0.1" armature="0.005"/>
|
| 58 |
-
<position inheritrange="1"/>
|
| 59 |
-
|
| 60 |
-
<default class="head">
|
| 61 |
-
<joint actuatorfrcrange="-7 7" damping="2"/>
|
| 62 |
-
<position kp="20"/>
|
| 63 |
-
<default class="head_yaw">
|
| 64 |
-
<joint axis="0 0 1" range="-1.57 1.57"/>
|
| 65 |
-
</default>
|
| 66 |
-
<default class="head_pitch">
|
| 67 |
-
<joint axis="0 1 0" range="-0.35 1.22"/>
|
| 68 |
-
</default>
|
| 69 |
-
</default>
|
| 70 |
-
<default class="shoulder">
|
| 71 |
-
<joint actuatorfrcrange="-18 18" damping="2"/>
|
| 72 |
-
<position kp="20"/>
|
| 73 |
-
<default class="shoulder_pitch">
|
| 74 |
-
<joint axis="0 1 0" range="-3.31 1.22"/>
|
| 75 |
-
</default>
|
| 76 |
-
<default class="shoulder_roll">
|
| 77 |
-
<joint axis="1 0 0"/>
|
| 78 |
-
</default>
|
| 79 |
-
</default>
|
| 80 |
-
<default class="elbow">
|
| 81 |
-
<joint actuatorfrcrange="-18 18" damping="2"/>
|
| 82 |
-
<position kp="20"/>
|
| 83 |
-
<default class="elbow_pitch">
|
| 84 |
-
<joint axis="0 1 0" range="-2.27 2.27"/>
|
| 85 |
-
</default>
|
| 86 |
-
<default class="elbow_yaw">
|
| 87 |
-
<joint axis="0 0 1"/>
|
| 88 |
-
</default>
|
| 89 |
-
</default>
|
| 90 |
-
<default class="waist">
|
| 91 |
-
<joint axis="0 0 1" range="-1.57 1.57" actuatorfrcrange="-30 30" damping="3"/>
|
| 92 |
-
<position kp="50"/>
|
| 93 |
-
</default>
|
| 94 |
-
<default class="hip">
|
| 95 |
-
<default class="hip_pitch">
|
| 96 |
-
<joint axis="0 1 0" range="-1.8 1.57" actuatorfrcrange="-45 45" damping="3"/>
|
| 97 |
-
<position kp="30"/>
|
| 98 |
-
</default>
|
| 99 |
-
<default class="hip_roll">
|
| 100 |
-
<joint axis="1 0 0" actuatorfrcrange="-30 30" damping="3"/>
|
| 101 |
-
<position kp="30"/>
|
| 102 |
-
</default>
|
| 103 |
-
<default class="hip_yaw">
|
| 104 |
-
<joint axis="0 0 1" range="-1 1" actuatorfrcrange="-30 30" damping="3"/>
|
| 105 |
-
<position kp="30"/>
|
| 106 |
-
</default>
|
| 107 |
-
</default>
|
| 108 |
-
<default class="knee">
|
| 109 |
-
<joint axis="0 1 0" range="0 2.34" actuatorfrcrange="-60 60" damping="3"/>
|
| 110 |
-
<position kp="30"/>
|
| 111 |
-
</default>
|
| 112 |
-
<default class="ankle">
|
| 113 |
-
<position kp="10"/>
|
| 114 |
-
<joint damping="3"/>
|
| 115 |
-
<default class="ankle_pitch">
|
| 116 |
-
<joint axis="0 1 0" range="-0.87 0.35" actuatorfrcrange="-20 20"/>
|
| 117 |
-
</default>
|
| 118 |
-
<default class="ankle_roll">
|
| 119 |
-
<joint axis="1 0 0" range="-0.44 0.44" actuatorfrcrange="-15 15"/>
|
| 120 |
-
</default>
|
| 121 |
</default>
|
| 122 |
</default>
|
| 123 |
</default>
|
| 124 |
|
| 125 |
<worldbody>
|
| 126 |
-
<
|
| 127 |
-
|
| 128 |
-
<
|
|
|
|
| 129 |
<inertial pos="0.0551365 -1.42058e-06 0.105062" quat="0.99996 1.40561e-05 -0.00899532 -1.39249e-05" mass="11.7"
|
| 130 |
diaginertia="0.0915404 0.0767787 0.0556055"/>
|
| 131 |
<site name="imu"/>
|
| 132 |
-
<camera name="track" pos="1.248 -0.947 0.5" xyaxes="0.628 0.779 -0.000 -0.274 0.221 0.936" mode="trackcom"/>
|
| 133 |
<geom class="visual" material="light_gray" mesh="Trunk"/>
|
| 134 |
<geom class="collision" size="0.075 0.1 0.15" pos="0.06 0 0.12" type="box"/>
|
| 135 |
<body name="H1" pos="0.0625 0 0.243">
|
| 136 |
<inertial pos="-0.000508 -0.001403 0.057432" quat="0.763881 -0.0132172 0.00173419 0.645219" mass="0.44391"
|
| 137 |
diaginertia="0.000241549 0.00022351 0.000149941"/>
|
| 138 |
-
<joint name="AAHead_yaw"
|
| 139 |
<geom class="visual" mesh="H1"/>
|
| 140 |
<body name="H2" pos="0 0 0.06185">
|
|
|
|
| 141 |
<inertial pos="0.007802 0.001262 0.098631" quat="0.988453 0.106172 -0.0745686 -0.0782786" mass="0.631019"
|
| 142 |
diaginertia="0.00203553 0.00192467 0.00172381"/>
|
| 143 |
-
<joint name="Head_pitch"
|
| 144 |
<geom class="visual" mesh="H2"/>
|
| 145 |
<geom class="collision" size="0.08" pos="0.01 0 0.11"/>
|
| 146 |
</body>
|
|
@@ -148,26 +79,28 @@
|
|
| 148 |
<body name="AL1" pos="0.0575 0.1063 0.219" quat="1 0 0.000440565 0">
|
| 149 |
<inertial pos="-0.000677 0.044974 0" quat="0.50423 0.495734 -0.50423 0.495734" mass="0.53"
|
| 150 |
diaginertia="0.001367 0.00129329 0.000292711"/>
|
| 151 |
-
<joint name="Left_Shoulder_Pitch"
|
| 152 |
<geom class="visual" material="light_gray" mesh="AL1"/>
|
| 153 |
<body name="AL2" pos="0 0.047 0">
|
|
|
|
| 154 |
<inertial pos="0.003862 0.037976 0" quat="0.487991 0.511727 -0.487991 0.511727" mass="0.16"
|
| 155 |
diaginertia="0.000401 0.00034538 0.00017662"/>
|
| 156 |
-
<joint name="Left_Shoulder_Roll" range="-1.74 1.57"
|
| 157 |
<geom class="visual" mesh="AL2"/>
|
| 158 |
<body name="AL3" pos="0.00025 0.0605 0">
|
| 159 |
<inertial pos="0 0.085353 -9.9e-05" quat="0.70641 0.707803 0 0" mass="1.02"
|
| 160 |
diaginertia="0.012869 0.012798 0.000620953"/>
|
| 161 |
-
<joint name="Left_Elbow_Pitch"
|
| 162 |
<geom class="visual" mesh="AL3"/>
|
| 163 |
<geom class="collision" size="0.03 0.075" pos="0 0.05 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
| 164 |
<body name="left_hand_link" pos="0 0.1471 0">
|
|
|
|
|
|
|
| 165 |
<inertial pos="-0.000108 0.109573 0.000591" quat="0.707866 0.706347 -5.22939e-05 -0.000214913"
|
| 166 |
mass="0.327214" diaginertia="0.008159 0.00813104 0.000214962"/>
|
| 167 |
-
<joint name="Left_Elbow_Yaw" range="-2.44 0"
|
| 168 |
<geom class="visual" mesh="left_hand_link"/>
|
| 169 |
<geom class="collision" size="0.03 0.0875" pos="0 0.13 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
| 170 |
-
<site name="left_hand" pos="0 .215 0"/>
|
| 171 |
</body>
|
| 172 |
</body>
|
| 173 |
</body>
|
|
@@ -175,73 +108,74 @@
|
|
| 175 |
<body name="AR1" pos="0.0575 -0.1063 0.219" quat="1 0 0.000440565 0">
|
| 176 |
<inertial pos="-0.000677 -0.044974 0" quat="0.50423 0.495734 -0.50423 0.495734" mass="0.53"
|
| 177 |
diaginertia="0.001367 0.00129329 0.000292711"/>
|
| 178 |
-
<joint name="Right_Shoulder_Pitch"
|
| 179 |
<geom class="visual" material="light_gray" mesh="AR1"/>
|
| 180 |
<body name="AR2" pos="0 -0.047 0">
|
|
|
|
| 181 |
<inertial pos="0.003862 -0.037976 0" quat="0.511727 0.487991 -0.511727 0.487991" mass="0.16"
|
| 182 |
diaginertia="0.000401 0.00034538 0.00017662"/>
|
| 183 |
-
<joint name="Right_Shoulder_Roll" range="-1.57 1.74"
|
| 184 |
<geom class="visual" mesh="AR2"/>
|
| 185 |
<body name="AR3" pos="0.00025 -0.0605 0">
|
| 186 |
<inertial pos="0 -0.085353 -9.9e-05" quat="0.707803 0.70641 0 0" mass="1.02"
|
| 187 |
diaginertia="0.012869 0.012798 0.000620953"/>
|
| 188 |
-
<joint name="Right_Elbow_Pitch"
|
| 189 |
<geom class="visual" mesh="AR3"/>
|
| 190 |
<geom class="collision" size="0.03 0.075" pos="0 -0.05 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
| 191 |
<body name="right_hand_link" pos="0 -0.1471 0">
|
|
|
|
|
|
|
| 192 |
<inertial pos="-0.000108 -0.109573 0.000591" quat="0.706347 0.707866 0.000214913 5.22939e-05"
|
| 193 |
mass="0.327214" diaginertia="0.008159 0.00813104 0.000214962"/>
|
| 194 |
-
<joint name="Right_Elbow_Yaw" range="0 2.44"
|
| 195 |
<geom class="visual" mesh="right_hand_link"/>
|
| 196 |
<geom class="collision" size="0.03 0.0875" pos="0 -0.13 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
| 197 |
-
<site name="right_hand" pos="0 -.215 0"/>
|
| 198 |
</body>
|
| 199 |
</body>
|
| 200 |
</body>
|
| 201 |
</body>
|
| 202 |
<body name="Waist" pos="0.0625 0 -0.1155">
|
|
|
|
| 203 |
<inertial pos="0.002284 3e-06 0.007301" quat="0.983649 0.000360386 -0.180076 0.00269791" mass="2.581"
|
| 204 |
diaginertia="0.00536742 0.005299 0.00474258"/>
|
| 205 |
-
<joint name="Waist"
|
| 206 |
<geom class="visual" mesh="Waist"/>
|
| 207 |
<body name="Hip_Pitch_Left" pos="0 0.106 0">
|
| 208 |
<inertial pos="0.000534 -0.007296 -0.018083" quat="0.975141 0.2211 0.0145808 0.0017406" mass="1.021"
|
| 209 |
diaginertia="0.00180547 0.00145926 0.00125327"/>
|
| 210 |
-
<joint name="Left_Hip_Pitch"
|
| 211 |
<geom class="visual" material="light_gray" mesh="Hip_Pitch_Left"/>
|
| 212 |
<body name="Hip_Roll_Left" pos="0 0 -0.02">
|
|
|
|
| 213 |
<inertial pos="0.001101 2.4e-05 -0.05375" quat="0.707081 -0.00599604 -0.00599604 0.707081" mass="0.385"
|
| 214 |
diaginertia="0.001743 0.00151729 0.000514712"/>
|
| 215 |
-
<joint name="Left_Hip_Roll" range="-0.2 1.57"
|
| 216 |
<geom class="visual" mesh="Hip_Roll_Left"/>
|
| 217 |
<body name="Hip_Yaw_Left" pos="0 0 -0.081854">
|
| 218 |
<inertial pos="-0.007233 0.000206 -0.089184" quat="0.696808 -0.033953 -0.0315708 0.715758" mass="2.166"
|
| 219 |
diaginertia="0.0257334 0.0253024 0.00259215"/>
|
| 220 |
-
<joint name="Left_Hip_Yaw"
|
| 221 |
<geom class="visual" mesh="Hip_Yaw_Left"/>
|
| 222 |
<geom class="collision" size="0.05 0.08" type="cylinder"/>
|
| 223 |
<body name="Shank_Left" pos="-0.014 0 -0.134">
|
|
|
|
| 224 |
<inertial pos="-0.006012 0.000259 -0.124318" quat="0.997573 0.00144024 -0.023949 0.0653706" mass="1.73"
|
| 225 |
diaginertia="0.0346951 0.0345375 0.00185844"/>
|
| 226 |
-
<joint name="Left_Knee_Pitch"
|
| 227 |
<geom class="visual" mesh="Shank_Left"/>
|
| 228 |
<geom class="collision" size="0.05 0.075" pos="0 0 -0.12" type="cylinder"/>
|
| 229 |
<body name="Ankle_Cross_Left" pos="0 0 -0.28">
|
| 230 |
<inertial pos="-0.003722 0 -0.007981" quat="0.443136 0.551027 0.551027 0.443136" mass="0.073"
|
| 231 |
diaginertia="2.9e-05 2.56589e-05 1.13411e-05"/>
|
| 232 |
-
<joint name="Left_Ankle_Pitch"
|
| 233 |
<geom class="visual" mesh="Ankle_Cross_Left"/>
|
| 234 |
<body name="left_foot_link" pos="0 0.00025 -0.012">
|
|
|
|
| 235 |
<inertial pos="-0.000249 0 -0.00914" quat="0 0.620755 0 0.784005" mass="0.685"
|
| 236 |
diaginertia="0.00269786 0.002385 0.00218714"/>
|
| 237 |
-
<joint name="Left_Ankle_Roll"
|
| 238 |
<geom class="visual" mesh="left_foot_link"/>
|
| 239 |
-
<geom name="
|
| 240 |
-
<site name="left_foot"/>
|
| 241 |
-
<geom name="left_foot_1" class="foot_sphere" pos="0.1015 0.04 -0.02"/>
|
| 242 |
-
<geom name="left_foot_2" class="foot_sphere" pos="0.1015 -0.04 -0.02"/>
|
| 243 |
-
<geom name="left_foot_3" class="foot_sphere" pos="-0.1015 0.04 -0.02"/>
|
| 244 |
-
<geom name="left_foot_4" class="foot_sphere" pos="-0.1015 -0.04 -0.02"/>
|
| 245 |
</body>
|
| 246 |
</body>
|
| 247 |
</body>
|
|
@@ -251,41 +185,39 @@
|
|
| 251 |
<body name="Hip_Pitch_Right" pos="0 -0.106 0">
|
| 252 |
<inertial pos="0.000534 0.007514 -0.018082" quat="0.973446 -0.228403 0.0147148 -0.00419349" mass="1.021"
|
| 253 |
diaginertia="0.00180552 0.0014632 0.00124928"/>
|
| 254 |
-
<joint name="Right_Hip_Pitch"
|
| 255 |
<geom class="visual" material="light_gray" mesh="Hip_Pitch_Right"/>
|
| 256 |
<body name="Hip_Roll_Right" pos="0 0 -0.02">
|
|
|
|
| 257 |
<inertial pos="0.001099 2.4e-05 -0.053748" quat="0.707081 -0.00599604 -0.00599604 0.707081" mass="0.385"
|
| 258 |
diaginertia="0.001743 0.00151729 0.000514712"/>
|
| 259 |
-
<joint name="Right_Hip_Roll" range="-1.57 0.2"
|
| 260 |
<geom class="visual" mesh="Hip_Roll_Right"/>
|
| 261 |
<body name="Hip_Yaw_Right" pos="0 0 -0.081854">
|
| 262 |
<inertial pos="-0.007191 -0.000149 -0.08922" quat="0.714468 -0.0315638 -0.0336391 0.698146" mass="2.17"
|
| 263 |
diaginertia="0.0257623 0.0253298 0.00259389"/>
|
| 264 |
-
<joint name="Right_Hip_Yaw"
|
| 265 |
<geom class="visual" mesh="Hip_Yaw_Right"/>
|
| 266 |
<geom class="collision" size="0.05 0.08" type="cylinder"/>
|
| 267 |
<body name="Shank_Right" pos="-0.014 0 -0.134">
|
|
|
|
| 268 |
<inertial pos="-0.005741 -0.000541 -0.122602" quat="0.99926 -0.000580963 -0.023461 -0.0304754"
|
| 269 |
mass="1.79" diaginertia="0.0351717 0.0349574 0.00196589"/>
|
| 270 |
-
<joint name="Right_Knee_Pitch"
|
| 271 |
<geom class="visual" mesh="Shank_Right"/>
|
| 272 |
<geom class="collision" size="0.05 0.075" pos="0 0 -0.12" type="cylinder"/>
|
| 273 |
<body name="Ankle_Cross_Right" pos="0 0 -0.28">
|
| 274 |
<inertial pos="-0.003722 0 -0.007981" quat="0.443136 0.551027 0.551027 0.443136" mass="0.073"
|
| 275 |
diaginertia="2.9e-05 2.56589e-05 1.13411e-05"/>
|
| 276 |
-
<joint name="Right_Ankle_Pitch"
|
| 277 |
<geom class="visual" mesh="Ankle_Cross_Right"/>
|
| 278 |
<body name="right_foot_link" pos="0 -0.00025 -0.012">
|
|
|
|
| 279 |
<inertial pos="-0.000248 0 -0.00914" quat="0 0.620755 0 0.784005" mass="0.685"
|
| 280 |
diaginertia="0.00269786 0.002385 0.00218714"/>
|
| 281 |
-
<joint name="Right_Ankle_Roll"
|
| 282 |
<geom class="visual" mesh="right_foot_link"/>
|
| 283 |
-
<geom name="
|
| 284 |
-
<site name="right_foot"/>
|
| 285 |
-
<geom name="right_foot_1" class="foot_sphere" pos="0.1015 0.04 -0.02"/>
|
| 286 |
-
<geom name="right_foot_2" class="foot_sphere" pos="0.1015 -0.04 -0.02"/>
|
| 287 |
-
<geom name="right_foot_3" class="foot_sphere" pos="-0.1015 0.04 -0.02"/>
|
| 288 |
-
<geom name="right_foot_4" class="foot_sphere" pos="-0.1015 -0.04 -0.02"/>
|
| 289 |
</body>
|
| 290 |
</body>
|
| 291 |
</body>
|
|
@@ -296,37 +228,6 @@
|
|
| 296 |
</body>
|
| 297 |
</worldbody>
|
| 298 |
|
| 299 |
-
<actuator>
|
| 300 |
-
<position class="head_yaw" name="AAHead_yaw" joint="AAHead_yaw"/>
|
| 301 |
-
<position class="head_pitch" name="Head_pitch" joint="Head_pitch"/>
|
| 302 |
-
|
| 303 |
-
<position class="shoulder_pitch" name="Left_Shoulder_Pitch" joint="Left_Shoulder_Pitch"/>
|
| 304 |
-
<position class="shoulder_roll" name="Left_Shoulder_Roll" joint="Left_Shoulder_Roll"/>
|
| 305 |
-
<position class="elbow_pitch" name="Left_Elbow_Pitch" joint="Left_Elbow_Pitch"/>
|
| 306 |
-
<position class="elbow_yaw" name="Left_Elbow_Yaw" joint="Left_Elbow_Yaw"/>
|
| 307 |
-
|
| 308 |
-
<position class="shoulder_pitch" name="Right_Shoulder_Pitch" joint="Right_Shoulder_Pitch"/>
|
| 309 |
-
<position class="shoulder_roll" name="Right_Shoulder_Roll" joint="Right_Shoulder_Roll"/>
|
| 310 |
-
<position class="elbow_pitch" name="Right_Elbow_Pitch" joint="Right_Elbow_Pitch"/>
|
| 311 |
-
<position class="elbow_yaw" name="Right_Elbow_Yaw" joint="Right_Elbow_Yaw"/>
|
| 312 |
-
|
| 313 |
-
<position class="waist" name="Waist" joint="Waist"/>
|
| 314 |
-
|
| 315 |
-
<position class="hip_pitch" name="Left_Hip_Pitch" joint="Left_Hip_Pitch"/>
|
| 316 |
-
<position class="hip_roll" name="Left_Hip_Roll" joint="Left_Hip_Roll"/>
|
| 317 |
-
<position class="hip_yaw" name="Left_Hip_Yaw" joint="Left_Hip_Yaw"/>
|
| 318 |
-
<position class="knee" name="Left_Knee_Pitch" joint="Left_Knee_Pitch"/>
|
| 319 |
-
<position class="ankle_pitch" name="Left_Ankle_Pitch" joint="Left_Ankle_Pitch"/>
|
| 320 |
-
<position class="ankle_roll" name="Left_Ankle_Roll" joint="Left_Ankle_Roll"/>
|
| 321 |
-
|
| 322 |
-
<position class="hip_pitch" name="Right_Hip_Pitch" joint="Right_Hip_Pitch"/>
|
| 323 |
-
<position class="hip_roll" name="Right_Hip_Roll" joint="Right_Hip_Roll"/>
|
| 324 |
-
<position class="hip_yaw" name="Right_Hip_Yaw" joint="Right_Hip_Yaw"/>
|
| 325 |
-
<position class="knee" name="Right_Knee_Pitch" joint="Right_Knee_Pitch"/>
|
| 326 |
-
<position class="ankle_pitch" name="Right_Ankle_Pitch" joint="Right_Ankle_Pitch"/>
|
| 327 |
-
<position class="ankle_roll" name="Right_Ankle_Roll" joint="Right_Ankle_Roll"/>
|
| 328 |
-
</actuator>
|
| 329 |
-
|
| 330 |
<sensor>
|
| 331 |
<gyro site="imu" name="torso_gyro" />
|
| 332 |
<velocimeter site="imu" name="torso_vel" />
|
|
@@ -339,6 +240,32 @@
|
|
| 339 |
<framequat objtype="site" objname="imu" name="torso_quat" />
|
| 340 |
</sensor>
|
| 341 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 342 |
<keyframe>
|
| 343 |
<key name="home"
|
| 344 |
qpos="
|
|
|
|
| 39 |
|
| 40 |
<default>
|
| 41 |
<default class="t1">
|
| 42 |
+
<geom material="medium_gray"/>
|
| 43 |
<site rgba="1 0 0 1" size="0.01" group="5"/>
|
| 44 |
+
<joint damping="1" armature="0.1"/>
|
| 45 |
+
<position inheritrange="1" kp="75" kv="5"/>
|
| 46 |
<default class="visual">
|
| 47 |
+
<geom type="mesh" contype="0" conaffinity="0" group="0"/>
|
| 48 |
</default>
|
| 49 |
<default class="collision">
|
| 50 |
<geom group="3"/>
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 51 |
</default>
|
| 52 |
</default>
|
| 53 |
</default>
|
| 54 |
|
| 55 |
<worldbody>
|
| 56 |
+
<body name="Trunk" pos="0 0 .675" childclass="t1">
|
| 57 |
+
<light name="spotlight" mode="trackcom" pos="0 -2 50" dir="0 0 -1"/>
|
| 58 |
+
<site name="upper_body_mimic" class="mimic" pos="0.075 0.0 0.2"/>
|
| 59 |
+
<freejoint name="root"/>
|
| 60 |
<inertial pos="0.0551365 -1.42058e-06 0.105062" quat="0.99996 1.40561e-05 -0.00899532 -1.39249e-05" mass="11.7"
|
| 61 |
diaginertia="0.0915404 0.0767787 0.0556055"/>
|
| 62 |
<site name="imu"/>
|
|
|
|
| 63 |
<geom class="visual" material="light_gray" mesh="Trunk"/>
|
| 64 |
<geom class="collision" size="0.075 0.1 0.15" pos="0.06 0 0.12" type="box"/>
|
| 65 |
<body name="H1" pos="0.0625 0 0.243">
|
| 66 |
<inertial pos="-0.000508 -0.001403 0.057432" quat="0.763881 -0.0132172 0.00173419 0.645219" mass="0.44391"
|
| 67 |
diaginertia="0.000241549 0.00022351 0.000149941"/>
|
| 68 |
+
<joint name="AAHead_yaw" axis="0 0 1" range="-1.57 1.57" actuatorfrcrange="-7 7"/>
|
| 69 |
<geom class="visual" mesh="H1"/>
|
| 70 |
<body name="H2" pos="0 0 0.06185">
|
| 71 |
+
<site name="head_mimic" class="mimic" pos="0.0 0.0 0.08"/>
|
| 72 |
<inertial pos="0.007802 0.001262 0.098631" quat="0.988453 0.106172 -0.0745686 -0.0782786" mass="0.631019"
|
| 73 |
diaginertia="0.00203553 0.00192467 0.00172381"/>
|
| 74 |
+
<joint name="Head_pitch" axis="0 1 0" range="-0.35 1.22" actuatorfrcrange="-7 7"/>
|
| 75 |
<geom class="visual" mesh="H2"/>
|
| 76 |
<geom class="collision" size="0.08" pos="0.01 0 0.11"/>
|
| 77 |
</body>
|
|
|
|
| 79 |
<body name="AL1" pos="0.0575 0.1063 0.219" quat="1 0 0.000440565 0">
|
| 80 |
<inertial pos="-0.000677 0.044974 0" quat="0.50423 0.495734 -0.50423 0.495734" mass="0.53"
|
| 81 |
diaginertia="0.001367 0.00129329 0.000292711"/>
|
| 82 |
+
<joint name="Left_Shoulder_Pitch" axis="0 1 0" range="-3.31 1.22" actuatorfrcrange="-18 18"/>
|
| 83 |
<geom class="visual" material="light_gray" mesh="AL1"/>
|
| 84 |
<body name="AL2" pos="0 0.047 0">
|
| 85 |
+
<site name="left_shoulder_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 86 |
<inertial pos="0.003862 0.037976 0" quat="0.487991 0.511727 -0.487991 0.511727" mass="0.16"
|
| 87 |
diaginertia="0.000401 0.00034538 0.00017662"/>
|
| 88 |
+
<joint name="Left_Shoulder_Roll" axis="1 0 0" range="-1.74 1.57" actuatorfrcrange="-18 18"/>
|
| 89 |
<geom class="visual" mesh="AL2"/>
|
| 90 |
<body name="AL3" pos="0.00025 0.0605 0">
|
| 91 |
<inertial pos="0 0.085353 -9.9e-05" quat="0.70641 0.707803 0 0" mass="1.02"
|
| 92 |
diaginertia="0.012869 0.012798 0.000620953"/>
|
| 93 |
+
<joint name="Left_Elbow_Pitch" axis="0 1 0" range="-2.27 2.27" actuatorfrcrange="-18 18"/>
|
| 94 |
<geom class="visual" mesh="AL3"/>
|
| 95 |
<geom class="collision" size="0.03 0.075" pos="0 0.05 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
| 96 |
<body name="left_hand_link" pos="0 0.1471 0">
|
| 97 |
+
<site name="left_elbow_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 98 |
+
<site name="left_hand_mimic" class="mimic" pos="0.0 0.2 0.0"/>
|
| 99 |
<inertial pos="-0.000108 0.109573 0.000591" quat="0.707866 0.706347 -5.22939e-05 -0.000214913"
|
| 100 |
mass="0.327214" diaginertia="0.008159 0.00813104 0.000214962"/>
|
| 101 |
+
<joint name="Left_Elbow_Yaw" axis="0 0 1" range="-2.44 0" actuatorfrcrange="-18 18"/>
|
| 102 |
<geom class="visual" mesh="left_hand_link"/>
|
| 103 |
<geom class="collision" size="0.03 0.0875" pos="0 0.13 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
|
|
|
| 104 |
</body>
|
| 105 |
</body>
|
| 106 |
</body>
|
|
|
|
| 108 |
<body name="AR1" pos="0.0575 -0.1063 0.219" quat="1 0 0.000440565 0">
|
| 109 |
<inertial pos="-0.000677 -0.044974 0" quat="0.50423 0.495734 -0.50423 0.495734" mass="0.53"
|
| 110 |
diaginertia="0.001367 0.00129329 0.000292711"/>
|
| 111 |
+
<joint name="Right_Shoulder_Pitch" axis="0 1 0" range="-3.31 1.22" actuatorfrcrange="-18 18"/>
|
| 112 |
<geom class="visual" material="light_gray" mesh="AR1"/>
|
| 113 |
<body name="AR2" pos="0 -0.047 0">
|
| 114 |
+
<site name="right_shoulder_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 115 |
<inertial pos="0.003862 -0.037976 0" quat="0.511727 0.487991 -0.511727 0.487991" mass="0.16"
|
| 116 |
diaginertia="0.000401 0.00034538 0.00017662"/>
|
| 117 |
+
<joint name="Right_Shoulder_Roll" axis="1 0 0" range="-1.57 1.74" actuatorfrcrange="-18 18"/>
|
| 118 |
<geom class="visual" mesh="AR2"/>
|
| 119 |
<body name="AR3" pos="0.00025 -0.0605 0">
|
| 120 |
<inertial pos="0 -0.085353 -9.9e-05" quat="0.707803 0.70641 0 0" mass="1.02"
|
| 121 |
diaginertia="0.012869 0.012798 0.000620953"/>
|
| 122 |
+
<joint name="Right_Elbow_Pitch" axis="0 1 0" range="-2.27 2.27" actuatorfrcrange="-18 18"/>
|
| 123 |
<geom class="visual" mesh="AR3"/>
|
| 124 |
<geom class="collision" size="0.03 0.075" pos="0 -0.05 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
| 125 |
<body name="right_hand_link" pos="0 -0.1471 0">
|
| 126 |
+
<site name="right_elbow_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 127 |
+
<site name="right_hand_mimic" class="mimic" pos="0.0 -0.2 0.0"/>
|
| 128 |
<inertial pos="-0.000108 -0.109573 0.000591" quat="0.706347 0.707866 0.000214913 5.22939e-05"
|
| 129 |
mass="0.327214" diaginertia="0.008159 0.00813104 0.000214962"/>
|
| 130 |
+
<joint name="Right_Elbow_Yaw" axis="0 0 1" range="0 2.44" actuatorfrcrange="-18 18"/>
|
| 131 |
<geom class="visual" mesh="right_hand_link"/>
|
| 132 |
<geom class="collision" size="0.03 0.0875" pos="0 -0.13 0" quat="0.707105 0.707108 0 0" type="cylinder"/>
|
|
|
|
| 133 |
</body>
|
| 134 |
</body>
|
| 135 |
</body>
|
| 136 |
</body>
|
| 137 |
<body name="Waist" pos="0.0625 0 -0.1155">
|
| 138 |
+
<site name="pelvis_mimic" class="mimic"/>
|
| 139 |
<inertial pos="0.002284 3e-06 0.007301" quat="0.983649 0.000360386 -0.180076 0.00269791" mass="2.581"
|
| 140 |
diaginertia="0.00536742 0.005299 0.00474258"/>
|
| 141 |
+
<joint name="Waist" axis="0 0 1" range="-1.57 1.57" actuatorfrcrange="-30 30"/>
|
| 142 |
<geom class="visual" mesh="Waist"/>
|
| 143 |
<body name="Hip_Pitch_Left" pos="0 0.106 0">
|
| 144 |
<inertial pos="0.000534 -0.007296 -0.018083" quat="0.975141 0.2211 0.0145808 0.0017406" mass="1.021"
|
| 145 |
diaginertia="0.00180547 0.00145926 0.00125327"/>
|
| 146 |
+
<joint name="Left_Hip_Pitch" axis="0 1 0" range="-1.8 1.57" actuatorfrcrange="-45 45"/>
|
| 147 |
<geom class="visual" material="light_gray" mesh="Hip_Pitch_Left"/>
|
| 148 |
<body name="Hip_Roll_Left" pos="0 0 -0.02">
|
| 149 |
+
<site name="left_hip_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 150 |
<inertial pos="0.001101 2.4e-05 -0.05375" quat="0.707081 -0.00599604 -0.00599604 0.707081" mass="0.385"
|
| 151 |
diaginertia="0.001743 0.00151729 0.000514712"/>
|
| 152 |
+
<joint name="Left_Hip_Roll" axis="1 0 0" range="-0.2 1.57" actuatorfrcrange="-30 30"/>
|
| 153 |
<geom class="visual" mesh="Hip_Roll_Left"/>
|
| 154 |
<body name="Hip_Yaw_Left" pos="0 0 -0.081854">
|
| 155 |
<inertial pos="-0.007233 0.000206 -0.089184" quat="0.696808 -0.033953 -0.0315708 0.715758" mass="2.166"
|
| 156 |
diaginertia="0.0257334 0.0253024 0.00259215"/>
|
| 157 |
+
<joint name="Left_Hip_Yaw" axis="0 0 1" range="-1 1" actuatorfrcrange="-30 30"/>
|
| 158 |
<geom class="visual" mesh="Hip_Yaw_Left"/>
|
| 159 |
<geom class="collision" size="0.05 0.08" type="cylinder"/>
|
| 160 |
<body name="Shank_Left" pos="-0.014 0 -0.134">
|
| 161 |
+
<site name="left_knee_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 162 |
<inertial pos="-0.006012 0.000259 -0.124318" quat="0.997573 0.00144024 -0.023949 0.0653706" mass="1.73"
|
| 163 |
diaginertia="0.0346951 0.0345375 0.00185844"/>
|
| 164 |
+
<joint name="Left_Knee_Pitch" axis="0 1 0" range="0 2.34" actuatorfrcrange="-60 60"/>
|
| 165 |
<geom class="visual" mesh="Shank_Left"/>
|
| 166 |
<geom class="collision" size="0.05 0.075" pos="0 0 -0.12" type="cylinder"/>
|
| 167 |
<body name="Ankle_Cross_Left" pos="0 0 -0.28">
|
| 168 |
<inertial pos="-0.003722 0 -0.007981" quat="0.443136 0.551027 0.551027 0.443136" mass="0.073"
|
| 169 |
diaginertia="2.9e-05 2.56589e-05 1.13411e-05"/>
|
| 170 |
+
<joint name="Left_Ankle_Pitch" axis="0 1 0" range="-0.87 0.35" actuatorfrcrange="-20 20"/>
|
| 171 |
<geom class="visual" mesh="Ankle_Cross_Left"/>
|
| 172 |
<body name="left_foot_link" pos="0 0.00025 -0.012">
|
| 173 |
+
<site name="left_foot_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 174 |
<inertial pos="-0.000249 0 -0.00914" quat="0 0.620755 0 0.784005" mass="0.685"
|
| 175 |
diaginertia="0.00269786 0.002385 0.00218714"/>
|
| 176 |
+
<joint name="Left_Ankle_Roll" axis="1 0 0" range="-0.44 0.44" actuatorfrcrange="-15 15"/>
|
| 177 |
<geom class="visual" mesh="left_foot_link"/>
|
| 178 |
+
<geom name="left_foot_collision" class="collision" size="0.1115 0.05 0.015" pos="0.01 0 -0.015" type="box"/>
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 179 |
</body>
|
| 180 |
</body>
|
| 181 |
</body>
|
|
|
|
| 185 |
<body name="Hip_Pitch_Right" pos="0 -0.106 0">
|
| 186 |
<inertial pos="0.000534 0.007514 -0.018082" quat="0.973446 -0.228403 0.0147148 -0.00419349" mass="1.021"
|
| 187 |
diaginertia="0.00180552 0.0014632 0.00124928"/>
|
| 188 |
+
<joint name="Right_Hip_Pitch" axis="0 1 0" range="-1.8 1.57" actuatorfrcrange="-45 45"/>
|
| 189 |
<geom class="visual" material="light_gray" mesh="Hip_Pitch_Right"/>
|
| 190 |
<body name="Hip_Roll_Right" pos="0 0 -0.02">
|
| 191 |
+
<site name="right_hip_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 192 |
<inertial pos="0.001099 2.4e-05 -0.053748" quat="0.707081 -0.00599604 -0.00599604 0.707081" mass="0.385"
|
| 193 |
diaginertia="0.001743 0.00151729 0.000514712"/>
|
| 194 |
+
<joint name="Right_Hip_Roll" axis="1 0 0" range="-1.57 0.2" actuatorfrcrange="-30 30"/>
|
| 195 |
<geom class="visual" mesh="Hip_Roll_Right"/>
|
| 196 |
<body name="Hip_Yaw_Right" pos="0 0 -0.081854">
|
| 197 |
<inertial pos="-0.007191 -0.000149 -0.08922" quat="0.714468 -0.0315638 -0.0336391 0.698146" mass="2.17"
|
| 198 |
diaginertia="0.0257623 0.0253298 0.00259389"/>
|
| 199 |
+
<joint name="Right_Hip_Yaw" axis="0 0 1" range="-1 1" actuatorfrcrange="-30 30"/>
|
| 200 |
<geom class="visual" mesh="Hip_Yaw_Right"/>
|
| 201 |
<geom class="collision" size="0.05 0.08" type="cylinder"/>
|
| 202 |
<body name="Shank_Right" pos="-0.014 0 -0.134">
|
| 203 |
+
<site name="right_knee_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 204 |
<inertial pos="-0.005741 -0.000541 -0.122602" quat="0.99926 -0.000580963 -0.023461 -0.0304754"
|
| 205 |
mass="1.79" diaginertia="0.0351717 0.0349574 0.00196589"/>
|
| 206 |
+
<joint name="Right_Knee_Pitch" axis="0 1 0" range="0 2.34" actuatorfrcrange="-60 60"/>
|
| 207 |
<geom class="visual" mesh="Shank_Right"/>
|
| 208 |
<geom class="collision" size="0.05 0.075" pos="0 0 -0.12" type="cylinder"/>
|
| 209 |
<body name="Ankle_Cross_Right" pos="0 0 -0.28">
|
| 210 |
<inertial pos="-0.003722 0 -0.007981" quat="0.443136 0.551027 0.551027 0.443136" mass="0.073"
|
| 211 |
diaginertia="2.9e-05 2.56589e-05 1.13411e-05"/>
|
| 212 |
+
<joint name="Right_Ankle_Pitch" axis="0 1 0" range="-0.87 0.35" actuatorfrcrange="-20 20"/>
|
| 213 |
<geom class="visual" mesh="Ankle_Cross_Right"/>
|
| 214 |
<body name="right_foot_link" pos="0 -0.00025 -0.012">
|
| 215 |
+
<site name="right_foot_mimic" class="mimic" pos="0.0 0.0 0.0"/>
|
| 216 |
<inertial pos="-0.000248 0 -0.00914" quat="0 0.620755 0 0.784005" mass="0.685"
|
| 217 |
diaginertia="0.00269786 0.002385 0.00218714"/>
|
| 218 |
+
<joint name="Right_Ankle_Roll" axis="1 0 0" range="-0.44 0.44" actuatorfrcrange="-15 15"/>
|
| 219 |
<geom class="visual" mesh="right_foot_link"/>
|
| 220 |
+
<geom name="right_foot_collision" class="collision" size="0.1115 0.05 0.015" pos="0.01 0 -0.015" type="box"/>
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 221 |
</body>
|
| 222 |
</body>
|
| 223 |
</body>
|
|
|
|
| 228 |
</body>
|
| 229 |
</worldbody>
|
| 230 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 231 |
<sensor>
|
| 232 |
<gyro site="imu" name="torso_gyro" />
|
| 233 |
<velocimeter site="imu" name="torso_vel" />
|
|
|
|
| 240 |
<framequat objtype="site" objname="imu" name="torso_quat" />
|
| 241 |
</sensor>
|
| 242 |
|
| 243 |
+
<actuator>
|
| 244 |
+
<position class="t1" name="AAHead_yaw" joint="AAHead_yaw"/>
|
| 245 |
+
<position class="t1" name="Head_pitch" joint="Head_pitch"/>
|
| 246 |
+
<position class="t1" name="Left_Shoulder_Pitch" joint="Left_Shoulder_Pitch"/>
|
| 247 |
+
<position class="t1" name="Left_Shoulder_Roll" joint="Left_Shoulder_Roll"/>
|
| 248 |
+
<position class="t1" name="Left_Elbow_Pitch" joint="Left_Elbow_Pitch"/>
|
| 249 |
+
<position class="t1" name="Left_Elbow_Yaw" joint="Left_Elbow_Yaw"/>
|
| 250 |
+
<position class="t1" name="Right_Shoulder_Pitch" joint="Right_Shoulder_Pitch"/>
|
| 251 |
+
<position class="t1" name="Right_Shoulder_Roll" joint="Right_Shoulder_Roll"/>
|
| 252 |
+
<position class="t1" name="Right_Elbow_Pitch" joint="Right_Elbow_Pitch"/>
|
| 253 |
+
<position class="t1" name="Right_Elbow_Yaw" joint="Right_Elbow_Yaw"/>
|
| 254 |
+
<position class="t1" name="Waist" joint="Waist"/>
|
| 255 |
+
<position class="t1" name="Left_Hip_Pitch" joint="Left_Hip_Pitch"/>
|
| 256 |
+
<position class="t1" name="Left_Hip_Roll" joint="Left_Hip_Roll"/>
|
| 257 |
+
<position class="t1" name="Left_Hip_Yaw" joint="Left_Hip_Yaw"/>
|
| 258 |
+
<position class="t1" name="Left_Knee_Pitch" joint="Left_Knee_Pitch"/>
|
| 259 |
+
<position class="t1" name="Left_Ankle_Pitch" joint="Left_Ankle_Pitch"/>
|
| 260 |
+
<position class="t1" name="Left_Ankle_Roll" joint="Left_Ankle_Roll"/>
|
| 261 |
+
<position class="t1" name="Right_Hip_Pitch" joint="Right_Hip_Pitch"/>
|
| 262 |
+
<position class="t1" name="Right_Hip_Roll" joint="Right_Hip_Roll"/>
|
| 263 |
+
<position class="t1" name="Right_Hip_Yaw" joint="Right_Hip_Yaw"/>
|
| 264 |
+
<position class="t1" name="Right_Knee_Pitch" joint="Right_Knee_Pitch"/>
|
| 265 |
+
<position class="t1" name="Right_Ankle_Pitch" joint="Right_Ankle_Pitch"/>
|
| 266 |
+
<position class="t1" name="Right_Ankle_Roll" joint="Right_Ankle_Roll"/>
|
| 267 |
+
</actuator>
|
| 268 |
+
|
| 269 |
<keyframe>
|
| 270 |
<key name="home"
|
| 271 |
qpos="
|