256 lines
21 KiB
XML
256 lines
21 KiB
XML
|
<mujoco model="h1_2">
|
||
|
<compiler angle="radian" meshdir="meshes/" autolimits="true"/>
|
||
|
<asset>
|
||
|
<mesh name="pelvis" file="pelvis.STL"/>
|
||
|
<mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
|
||
|
<mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
|
||
|
<mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
|
||
|
<mesh name="left_knee_link" file="left_knee_link.STL"/>
|
||
|
<mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
|
||
|
<mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
|
||
|
<mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
|
||
|
<mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
|
||
|
<mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
|
||
|
<mesh name="right_knee_link" file="right_knee_link.STL"/>
|
||
|
<mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
|
||
|
<mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
|
||
|
<mesh name="torso_link" file="torso_link.STL"/>
|
||
|
<mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
|
||
|
<mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
|
||
|
<mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
|
||
|
<mesh name="left_elbow_link" file="left_elbow_link.STL"/>
|
||
|
<mesh name="left_wrist_roll_link" file="left_wrist_roll_link.STL"/>
|
||
|
<mesh name="left_wrist_pitch_link" file="left_wrist_pitch_link.STL"/>
|
||
|
<mesh name="wrist_yaw_link" file="wrist_yaw_link.STL"/>
|
||
|
<mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
|
||
|
<mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
|
||
|
<mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
|
||
|
<mesh name="right_elbow_link" file="right_elbow_link.STL"/>
|
||
|
<mesh name="right_wrist_roll_link" file="right_wrist_roll_link.STL"/>
|
||
|
<mesh name="right_wrist_pitch_link" file="right_wrist_pitch_link.STL"/>
|
||
|
<mesh name="logo_link" file="logo_link.STL"/>
|
||
|
</asset>
|
||
|
<worldbody>
|
||
|
<body name="pelvis" pos="0 0 1.03">
|
||
|
<inertial pos="-0.0004 3.7e-05 -0.046864" quat="0.497097 0.496809 -0.503132 0.502925" mass="5.983" diaginertia="0.0531565 0.0491678 0.00902583"/>
|
||
|
<joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="pelvis"/>
|
||
|
<geom size="0.05" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="left_hip_yaw_link" pos="0 0.0875 -0.1632">
|
||
|
<inertial pos="0 -0.026197 0.006647" quat="0.704899 -0.0553755 0.0548434 0.705013" mass="2.829" diaginertia="0.00574303 0.00455361 0.00349461"/>
|
||
|
<joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-0.43 0.43" actuatorfrcrange="-200 200"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_hip_yaw_link"/>
|
||
|
<geom size="0.01 0.01" pos="0.02 0 0" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="left_hip_pitch_link" pos="0 0.0755 0">
|
||
|
<inertial pos="-0.00781 -0.004724 -6.3e-05" quat="0.701575 0.711394 0.0330266 0.0249149" mass="2.92" diaginertia="0.00560661 0.00445055 0.00385068"/>
|
||
|
<joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.14 2.5" actuatorfrcrange="-200 200"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_hip_pitch_link"/>
|
||
|
<geom size="0.02 0.1" pos="0 0 -0.2" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="left_hip_roll_link">
|
||
|
<inertial pos="0.004171 -0.008576 -0.194509" quat="0.634842 0.0146079 0.0074063 0.772469" mass="4.962" diaginertia="0.0480229 0.0462788 0.00887409"/>
|
||
|
<joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.43 3.14" actuatorfrcrange="-200 200"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_hip_roll_link"/>
|
||
|
<geom size="0.02 0.005" pos="0 0.06 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="left_knee_link" pos="0 0 -0.4">
|
||
|
<inertial pos="0.000179 0.000121 -0.168936" quat="0.416585 0.0104983 0.00514003 0.909021" mass="3.839" diaginertia="0.0391044 0.038959 0.00501125"/>
|
||
|
<joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.12 2.19" actuatorfrcrange="-300 300"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_knee_link"/>
|
||
|
<geom size="0.02 0.1" pos="0 0 -0.2" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="left_ankle_pitch_link" pos="0 0 -0.4">
|
||
|
<inertial pos="-0.000294 0 -0.010794" quat="0.999984 0 -0.00574445 0" mass="0.102" diaginertia="2.39454e-05 2.1837e-05 1.34126e-05"/>
|
||
|
<joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.897334 0.523598" actuatorfrcrange="-60 60"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_ankle_pitch_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_ankle_pitch_link"/>
|
||
|
<body name="left_ankle_roll_link" pos="0 0 -0.02">
|
||
|
<inertial pos="0.029589 0 -0.015973" quat="0 0.725858 0 0.687845" mass="0.747" diaginertia="0.00359178 0.00343534 0.000640307"/>
|
||
|
<joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.261799 0.261799" actuatorfrcrange="-40 40"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_ankle_roll_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_ankle_roll_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="right_hip_yaw_link" pos="0 -0.0875 -0.1632">
|
||
|
<inertial pos="0 0.026197 0.006647" quat="0.705013 0.0548434 -0.0553755 0.704899" mass="2.829" diaginertia="0.00574303 0.00455361 0.00349461"/>
|
||
|
<joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-0.43 0.43" actuatorfrcrange="-200 200"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_hip_yaw_link"/>
|
||
|
<geom size="0.01 0.01" pos="0.02 0 0" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="right_hip_pitch_link" pos="0 -0.0755 0">
|
||
|
<inertial pos="-0.00781 0.004724 -6.3e-05" quat="0.711394 0.701575 -0.0249149 -0.0330266" mass="2.92" diaginertia="0.00560661 0.00445055 0.00385068"/>
|
||
|
<joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.14 2.5" actuatorfrcrange="-200 200"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_hip_pitch_link"/>
|
||
|
<geom size="0.02 0.1" pos="0 0 -0.2" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="right_hip_roll_link">
|
||
|
<inertial pos="0.004171 0.008576 -0.194509" quat="0.772469 0.0074063 0.0146079 0.634842" mass="4.962" diaginertia="0.0480229 0.0462788 0.00887409"/>
|
||
|
<joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-3.14 0.43" actuatorfrcrange="-200 200"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_hip_roll_link"/>
|
||
|
<geom size="0.02 0.005" pos="0 -0.06 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="right_knee_link" pos="0 0 -0.4">
|
||
|
<inertial pos="0.000179 -0.000121 -0.168936" quat="0.909021 0.00514003 0.0104983 0.416585" mass="3.839" diaginertia="0.0391044 0.038959 0.00501125"/>
|
||
|
<joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.12 2.19" actuatorfrcrange="-300 300"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_knee_link"/>
|
||
|
<geom size="0.02 0.1" pos="0 0 -0.2" type="cylinder" rgba="0.1 0.1 0.1 1"/>
|
||
|
<body name="right_ankle_pitch_link" pos="0 0 -0.4">
|
||
|
<inertial pos="-0.000294 0 -0.010794" quat="0.999984 0 -0.00574445 0" mass="0.102" diaginertia="2.39454e-05 2.1837e-05 1.34126e-05"/>
|
||
|
<joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.897334 0.523598" actuatorfrcrange="-60 60"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_ankle_pitch_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_ankle_pitch_link"/>
|
||
|
<body name="right_ankle_roll_link" pos="0 0 -0.02">
|
||
|
<inertial pos="0.029589 0 -0.015973" quat="0 0.725858 0 0.687845" mass="0.747" diaginertia="0.00359178 0.00343534 0.000640307"/>
|
||
|
<joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.261799 0.261799" actuatorfrcrange="-40 40"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_ankle_roll_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_ankle_roll_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="torso_link">
|
||
|
<inertial pos="0.000489 0.002797 0.20484" quat="0.999989 -0.00130808 -0.00282289 -0.00349105" mass="17.789" diaginertia="0.487315 0.409628 0.127837"/>
|
||
|
<joint name="torso_joint" pos="0 0 0" axis="0 0 1" range="-2.35 2.35" actuatorfrcrange="-200 200"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="torso_link"/>
|
||
|
<geom size="0.04 0.08 0.05" pos="0 0 0.15" type="box" rgba="0.1 0.1 0.1 1"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 1 1 1" mesh="logo_link"/>
|
||
|
<site name="imu" size="0.01" pos="-0.04452 -0.01891 0.27756"/>
|
||
|
<body name="left_shoulder_pitch_link" pos="0 0.14806 0.42333" quat="0.991445 0.130526 0 0">
|
||
|
<inertial pos="0.003053 0.06042 -0.0059" quat="0.761799 0.645681 -0.0378496 -0.0363943" mass="1.327" diaginertia="0.000588757 0.00053309 0.000393023"/>
|
||
|
<joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.14 1.57" actuatorfrcrange="-40 40"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_shoulder_pitch_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_shoulder_pitch_link"/>
|
||
|
<body name="left_shoulder_roll_link" pos="0.0342 0.061999 -0.0060011" quat="0.991445 -0.130526 0 0">
|
||
|
<inertial pos="-0.030932 -1e-06 -0.10609" quat="0.986055 0.000456937 0.166408 0.00213553" mass="1.393" diaginertia="0.00200869 0.00193464 0.000449847"/>
|
||
|
<joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.38 3.4" actuatorfrcrange="-40 40"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_shoulder_roll_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_shoulder_roll_link"/>
|
||
|
<body name="left_shoulder_yaw_link" pos="-0.0342 0 -0.1456">
|
||
|
<inertial pos="0.004583 0.001128 -0.001128" quat="0.663644 -0.0108866 -0.0267235 0.747492" mass="1.505" diaginertia="0.00431782 0.00420697 0.000645658"/>
|
||
|
<joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.66 3.01" actuatorfrcrange="-18 18"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_shoulder_yaw_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_shoulder_yaw_link"/>
|
||
|
<body name="left_elbow_link" pos="0.006 0.0329 -0.182">
|
||
|
<inertial pos="0.077092 -0.028751 -0.009714" quat="0.544921 0.610781 0.423352 0.388305" mass="0.691" diaginertia="0.000942091 0.000905273 0.00023025"/>
|
||
|
<joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-0.95 3.18" actuatorfrcrange="-18 18"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_elbow_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_elbow_link"/>
|
||
|
<body name="left_wrist_roll_link" pos="0.121 -0.0329 -0.011">
|
||
|
<inertial pos="0.035281 -0.00232 0.000337" quat="0.334998 0.622198 -0.240131 0.66557" mass="0.683" diaginertia="0.00034681 0.000328248 0.000294628"/>
|
||
|
<joint name="left_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-3.01 2.75" actuatorfrcrange="-19 19"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_wrist_roll_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_wrist_roll_link"/>
|
||
|
<body name="left_wrist_pitch_link" pos="0.087 0 0">
|
||
|
<inertial pos="0.020395 3.6e-05 -0.002973" quat="0.915893 -0.228405 -0.327262 -0.0432527" mass="0.484" diaginertia="7.25675e-05 7.00325e-05 6.9381e-05"/>
|
||
|
<joint name="left_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.4625 0.4625" actuatorfrcrange="-19 19"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="left_wrist_pitch_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="left_wrist_pitch_link"/>
|
||
|
<body name="left_wrist_yaw_link" pos="0.02 0 0">
|
||
|
<inertial pos="0.027967 9.6e-05 0.000739" quat="0.704961 -0.0198461 -0.019614 0.708697" mass="0.124" diaginertia="0.000169999 0.000137463 8.46436e-05"/>
|
||
|
<joint name="left_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.27 1.27" actuatorfrcrange="-19 19"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="wrist_yaw_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
<body name="right_shoulder_pitch_link" pos="0 -0.14806 0.42333" quat="0.991445 -0.130526 0 0">
|
||
|
<inertial pos="0.003053 -0.06042 -0.0059" quat="0.645681 0.761799 0.0363943 0.0378496" mass="1.327" diaginertia="0.000588757 0.00053309 0.000393023"/>
|
||
|
<joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.14 1.57" actuatorfrcrange="-40 40"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_shoulder_pitch_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_shoulder_pitch_link"/>
|
||
|
<body name="right_shoulder_roll_link" pos="0.0342 -0.061999 -0.0060011" quat="0.991445 0.130526 0 0">
|
||
|
<inertial pos="-0.030932 1e-06 -0.10609" quat="0.986055 -0.000456937 0.166408 -0.00213553" mass="1.393" diaginertia="0.00200869 0.00193464 0.000449847"/>
|
||
|
<joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-3.4 0.38" actuatorfrcrange="-40 40"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_shoulder_roll_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_shoulder_roll_link"/>
|
||
|
<body name="right_shoulder_yaw_link" pos="-0.0342 0 -0.1456">
|
||
|
<inertial pos="0.004583 -0.001128 -0.001128" quat="0.747492 -0.0267235 -0.0108866 0.663644" mass="1.505" diaginertia="0.00431782 0.00420697 0.000645658"/>
|
||
|
<joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-3.01 2.66" actuatorfrcrange="-18 18"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_shoulder_yaw_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_shoulder_yaw_link"/>
|
||
|
<body name="right_elbow_link" pos="0.006 -0.0329 -0.182">
|
||
|
<inertial pos="0.077092 0.028751 -0.009714" quat="0.388305 0.423352 0.610781 0.544921" mass="0.691" diaginertia="0.000942091 0.000905273 0.00023025"/>
|
||
|
<joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-0.95 3.18" actuatorfrcrange="-18 18"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_elbow_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_elbow_link"/>
|
||
|
<body name="right_wrist_roll_link" pos="0.121 0.0329 -0.011">
|
||
|
<inertial pos="0.035281 -0.00232 0.000337" quat="0.334998 0.622198 -0.240131 0.66557" mass="0.683" diaginertia="0.00034681 0.000328248 0.000294628"/>
|
||
|
<joint name="right_wrist_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.75 3.01" actuatorfrcrange="-19 19"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_wrist_roll_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_wrist_roll_link"/>
|
||
|
<body name="right_wrist_pitch_link" pos="0.087 0 0">
|
||
|
<inertial pos="0.020395 3.6e-05 -0.002973" quat="0.915893 -0.228405 -0.327262 -0.0432527" mass="0.484" diaginertia="7.25675e-05 7.00325e-05 6.9381e-05"/>
|
||
|
<joint name="right_wrist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.4625 0.4625" actuatorfrcrange="-19 19"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="right_wrist_pitch_link"/>
|
||
|
<geom type="mesh" rgba="0.1 0.1 0.1 1" mesh="right_wrist_pitch_link"/>
|
||
|
<body name="right_wrist_yaw_link" pos="0.02 0 0">
|
||
|
<inertial pos="0.027967 -9.6e-05 0.000739" quat="0.708697 -0.019614 -0.0198461 0.704961" mass="0.124" diaginertia="0.000169999 0.000137463 8.46436e-05"/>
|
||
|
<joint name="right_wrist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-1.27 1.27" actuatorfrcrange="-19 19"/>
|
||
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.1 0.1 0.1 1" mesh="wrist_yaw_link"/>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</body>
|
||
|
</worldbody>
|
||
|
|
||
|
|
||
|
<actuator>
|
||
|
<motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
|
||
|
<motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
|
||
|
<motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
|
||
|
<motor name="left_knee_joint" joint="left_knee_joint"/>
|
||
|
<motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
|
||
|
<motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
|
||
|
<motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
|
||
|
<motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
|
||
|
<motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
|
||
|
<motor name="right_knee_joint" joint="right_knee_joint"/>
|
||
|
<motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
|
||
|
<motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
|
||
|
<motor name="torso_joint" joint="torso_joint"/>
|
||
|
<motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
|
||
|
<motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
|
||
|
<motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
|
||
|
<motor name="left_elbow_joint" joint="left_elbow_joint"/>
|
||
|
<motor name="left_wrist_roll_joint" joint="left_wrist_roll_joint"/>
|
||
|
<motor name="left_wrist_pitch_joint" joint="left_wrist_pitch_joint"/>
|
||
|
<motor name="left_wrist_yaw_joint" joint="left_wrist_yaw_joint"/>
|
||
|
<motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
|
||
|
<motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
|
||
|
<motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
|
||
|
<motor name="right_elbow_joint" joint="right_elbow_joint"/>
|
||
|
<motor name="right_wrist_roll_joint" joint="right_wrist_roll_joint"/>
|
||
|
<motor name="right_wrist_pitch_joint" joint="right_wrist_pitch_joint"/>
|
||
|
<motor name="right_wrist_yaw_joint" joint="right_wrist_yaw_joint"/>
|
||
|
</actuator>
|
||
|
|
||
|
<sensor>
|
||
|
<gyro name="imu-angular-velocity" site="imu" noise="5e-4" cutoff="34.9"/>
|
||
|
<accelerometer name="imu-linear-acceleration" site="imu" noise="1e-2" cutoff="157"/>
|
||
|
</sensor>
|
||
|
|
||
|
<!-- setup scene -->
|
||
|
<statistic center="1.0 0.7 1.5" extent="0.8"/>
|
||
|
<visual>
|
||
|
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
|
||
|
<rgba haze="0.15 0.25 0.35 1"/>
|
||
|
<global azimuth="-140" elevation="-20"/>
|
||
|
</visual>
|
||
|
<asset>
|
||
|
<texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
|
||
|
<texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
|
||
|
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
|
||
|
</asset>
|
||
|
<worldbody>
|
||
|
<light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
|
||
|
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
|
||
|
</worldbody>
|
||
|
</mujoco>
|