Datasets:

ArXiv:
License:
Fisher-Wang's picture
Upload mjx_h1.xml (#12)
c982117 verified
<mujoco model="h1">
<compiler angle="radian" meshdir="assets" autolimits="true"/>
<default>
<default class="h1">
<geom type="mesh"/>
<joint damping="1" armature="0.1"/>
<default class="visual">
<geom contype="0" conaffinity="0" group="2" material="black"/>
</default>
<default class="collision">
<geom group="3" mass="0" density="0"/>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
<default class="hip">
<position forcerange="-200 200" kp="200" kv="5"/>
</default>
<default class="knee">
<position forcerange="-300 300" kp="300" kv="6"/>
</default>
<default class="ankle">
<position forcerange="-40 40" kp="40" kv="2"/>
</default>
<default class="torso">
<position forcerange="-200 200" kp="300" kv="6"/>
</default>
<default class="shoulder1">
<position forcerange="-40 40" kp="100" kv="2"/>
</default>
<default class="shoulder2">
<position forcerange="-18 18" kp="100" kv="2"/>
</default>
<default class="elbow">
<position forcerange="-18 18" kp="100" kv="2"/>
</default>
</default>
</default>
<asset>
<material name="black" rgba="0.1 0.1 0.1 1"/>
<material name="white" rgba="1 1 1 1"/>
<mesh file="pelvis.stl"/>
<mesh file="left_hip_yaw_link.stl"/>
<mesh file="left_hip_roll_link.stl"/>
<mesh file="left_hip_pitch_link.stl"/>
<mesh file="left_knee_link.stl"/>
<mesh file="left_ankle_link.stl"/>
<mesh file="right_hip_yaw_link.stl"/>
<mesh file="right_hip_roll_link.stl"/>
<mesh file="right_hip_pitch_link.stl"/>
<mesh file="right_knee_link.stl"/>
<mesh file="right_ankle_link.stl"/>
<mesh file="torso_link.stl"/>
<mesh file="left_shoulder_pitch_link.stl"/>
<mesh file="left_shoulder_roll_link.stl"/>
<mesh file="left_shoulder_yaw_link.stl"/>
<mesh file="left_elbow_link.stl"/>
<mesh file="right_shoulder_pitch_link.stl"/>
<mesh file="right_shoulder_roll_link.stl"/>
<mesh file="right_shoulder_yaw_link.stl"/>
<mesh file="right_elbow_link.stl"/>
<mesh file="logo_link.stl"/>
</asset>
<worldbody>
<light pos="0 0 10" castshadow="false" directional="true"
ambient="0.3 0.3 0.3" diffuse="0.7 0.7 0.7" specular="0.1 0.1 0.1"/>
<body name="pelvis" pos="0 0 0" childclass="h1">
<camera name="cam_default" pos="2 3 0" mode="trackcom" xyaxes="-1 0.5 0 0 0 1"/>
<inertial pos="-0.0002 4e-05 -0.04522" quat="0.498303 0.499454 -0.500496 0.501741" mass="5.39"
diaginertia="0.0490211 0.0445821 0.00824619"/>
<geom class="visual" mesh="pelvis"/>
<body name="left_hip_yaw_link" pos="0 0.0875 -0.1742">
<inertial pos="-0.04923 0.0001 0.0072" quat="0.69699 0.219193 0.233287 0.641667" mass="2.244"
diaginertia="0.00304494 0.00296885 0.00189201"/>
<joint name="left_hip_yaw" axis="0 0 1" range="-0.43 0.43"/>
<geom class="visual" mesh="left_hip_yaw_link"/>
<body name="left_hip_roll_link" pos="0.039468 0 0">
<inertial pos="-0.0058 -0.00319 -9e-05" quat="0.0438242 0.70721 -0.0729075 0.701867" mass="2.232"
diaginertia="0.00243264 0.00225325 0.00205492"/>
<joint name="left_hip_roll" axis="1 0 0" range="-0.43 0.43"/>
<geom class="visual" mesh="left_hip_roll_link"/>
<body name="left_hip_pitch_link" pos="0 0.11536 0">
<inertial pos="0.00746 -0.02346 -0.08193" quat="0.979828 0.0513522 -0.0169854 -0.192382" mass="4.152"
diaginertia="0.0829503 0.0821457 0.00510909"/>
<joint name="left_hip_pitch" axis="0 1 0" range="-3.14 2.53"/>
<geom class="visual" mesh="left_hip_pitch_link"/>
<body name="left_knee_link" pos="0 0 -0.4">
<inertial pos="-0.00136 -0.00512 -0.1384" quat="0.626132 -0.034227 -0.0416277 0.777852" mass="1.721"
diaginertia="0.0125237 0.0123104 0.0019428"/>
<joint name="left_knee" axis="0 1 0" range="-0.26 2.05"/>
<geom class="visual" mesh="left_knee_link"/>
<body name="left_ankle_link" pos="0 0 -0.4">
<inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
diaginertia="0.00362 0.00355701 0.000149987"/>
<joint name="left_ankle" axis="0 1 0" range="-0.87 0.52"/>
<geom class="visual" mesh="left_ankle_link"/>
<geom size="0.15 0.015 0.015" pos="0.05 0 -0.055" type="box" class="collision"/>
<site name="left_foot" pos="0. 0 -0.05" rgba="0 1 0 1" size="0.2"/>
</body>
</body>
</body>
</body>
</body>
<body name="right_hip_yaw_link" pos="0 -0.0875 -0.1742">
<inertial pos="-0.04923 -0.0001 0.0072" quat="0.641667 0.233287 0.219193 0.69699" mass="2.244"
diaginertia="0.00304494 0.00296885 0.00189201"/>
<joint name="right_hip_yaw" axis="0 0 1" range="-0.43 0.43"/>
<geom class="visual" mesh="right_hip_yaw_link"/>
<body name="right_hip_roll_link" pos="0.039468 0 0">
<inertial pos="-0.0058 0.00319 -9e-05" quat="-0.0438242 0.70721 0.0729075 0.701867" mass="2.232"
diaginertia="0.00243264 0.00225325 0.00205492"/>
<joint name="right_hip_roll" axis="1 0 0" range="-0.43 0.43"/>
<geom class="visual" mesh="right_hip_roll_link"/>
<body name="right_hip_pitch_link" pos="0 -0.11536 0">
<inertial pos="0.00746 0.02346 -0.08193" quat="0.979828 -0.0513522 -0.0169854 0.192382" mass="4.152"
diaginertia="0.0829503 0.0821457 0.00510909"/>
<joint name="right_hip_pitch" axis="0 1 0" range="-3.14 2.53"/>
<geom class="visual" mesh="right_hip_pitch_link"/>
<body name="right_knee_link" pos="0 0 -0.4">
<inertial pos="-0.00136 0.00512 -0.1384" quat="0.777852 -0.0416277 -0.034227 0.626132" mass="1.721"
diaginertia="0.0125237 0.0123104 0.0019428"/>
<joint name="right_knee" axis="0 1 0" range="-0.26 2.05"/>
<geom class="visual" mesh="right_knee_link"/>
<body name="right_ankle_link" pos="0 0 -0.4">
<inertial pos="0.048568 0 -0.045609" quat="0.489385 0.510394 0.510394 0.489385" mass="0.552448"
diaginertia="0.00362 0.00355701 0.000149987"/>
<joint name="right_ankle" axis="0 1 0" range="-0.87 0.52"/>
<geom class="visual" mesh="right_ankle_link"/>
<geom size="0.15 0.015 0.015" pos="0.05 0 -0.055" type="box" class="collision"/>
<site name="right_foot" pos="0. 0 -0.05" rgba="0 1 0 1" size="0.2"/>
</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" axis="0 0 1" range="-2.35 2.35"/>
<geom class="visual" mesh="torso_link"/>
<site name="head" class="visual" size="0.01" pos="0 0 0.7" rgba="1 1 1 1"/>
<geom class="visual" material="white" mesh="logo_link"/>
<site name="imu" size="0.01" pos="-0.04452 0.0 0.27756"/>
<body name="left_shoulder_pitch_link" pos="0.0055 0.15535 0.42999" quat="0.976296 0.216438 0 0">
<inertial pos="0.005045 0.053657 -0.015715" quat="0.814858 0.579236 -0.0201072 -0.00936488" mass="1.033"
diaginertia="0.00129936 0.000987113 0.000858198"/>
<joint name="left_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/>
<geom class="visual" mesh="left_shoulder_pitch_link"/>
<body name="left_shoulder_roll_link" pos="-0.0055 0.0565 -0.0165" quat="0.976296 -0.216438 0 0">
<inertial pos="0.000679 0.00115 -0.094076" quat="0.732491 0.00917179 0.0766656 0.676384" mass="0.793"
diaginertia="0.00170388 0.00158256 0.00100336"/>
<joint name="left_shoulder_roll" axis="1 0 0" range="-0.34 3.11"/>
<geom class="visual" mesh="left_shoulder_roll_link"/>
<body name="left_shoulder_yaw_link" pos="0 0 -0.1343">
<inertial pos="0.01365 0.002767 -0.16266" quat="0.703042 -0.0331229 -0.0473362 0.708798" mass="0.839"
diaginertia="0.00408038 0.00370367 0.000622687"/>
<joint name="left_shoulder_yaw" axis="0 0 1" range="-1.3 4.45"/>
<geom class="visual" mesh="left_shoulder_yaw_link"/>
<body name="left_elbow_link" pos="0.0185 0 -0.198">
<inertial pos="0.15908 -0.000144 -0.015776" quat="0.0765232 0.720327 0.0853116 0.684102" mass="0.669"
diaginertia="0.00601829 0.00600579 0.000408305"/>
<joint name="left_elbow" axis="0 1 0" range="-1.25 2.61"/>
<geom class="visual" mesh="left_elbow_link"/>
<site name="left_hand" pos="0.31 0 -0.01" rgba="0 1 0 1" size="0.01"/>
</body>
</body>
</body>
</body>
<body name="right_shoulder_pitch_link" pos="0.0055 -0.15535 0.42999" quat="0.976296 -0.216438 0 0">
<inertial pos="0.005045 -0.053657 -0.015715" quat="0.579236 0.814858 0.00936488 0.0201072" mass="1.033"
diaginertia="0.00129936 0.000987113 0.000858198"/>
<joint name="right_shoulder_pitch" axis="0 1 0" range="-2.87 2.87"/>
<geom class="visual" mesh="right_shoulder_pitch_link"/>
<body name="right_shoulder_roll_link" pos="-0.0055 -0.0565 -0.0165" quat="0.976296 0.216438 0 0">
<inertial pos="0.000679 -0.00115 -0.094076" quat="0.676384 0.0766656 0.00917179 0.732491" mass="0.793"
diaginertia="0.00170388 0.00158256 0.00100336"/>
<joint name="right_shoulder_roll" axis="1 0 0" range="-3.11 0.34"/>
<geom class="visual" mesh="right_shoulder_roll_link"/>
<body name="right_shoulder_yaw_link" pos="0 0 -0.1343">
<inertial pos="0.01365 -0.002767 -0.16266" quat="0.708798 -0.0473362 -0.0331229 0.703042" mass="0.839"
diaginertia="0.00408038 0.00370367 0.000622687"/>
<joint name="right_shoulder_yaw" axis="0 0 1" range="-4.45 1.3"/>
<geom class="visual" mesh="right_shoulder_yaw_link"/>
<body name="right_elbow_link" pos="0.0185 0 -0.198">
<inertial pos="0.15908 0.000144 -0.015776" quat="-0.0765232 0.720327 -0.0853116 0.684102" mass="0.669"
diaginertia="0.00601829 0.00600579 0.000408305"/>
<joint name="right_elbow" axis="0 1 0" range="-1.25 2.61"/>
<geom class="visual" mesh="right_elbow_link"/>
<site name="right_hand" pos="0.31 0 -0.01"/>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<position name="left_hip_yaw" joint="left_hip_yaw" ctrlrange="-0.43 0.43" class="hip" />
<position name="left_hip_roll" joint="left_hip_roll" ctrlrange="-0.43 0.43" class="hip" />
<position name="left_hip_pitch" joint="left_hip_pitch" ctrlrange="-3.14 2.53" class="hip" />
<position name="left_knee" joint="left_knee" ctrlrange="-0.26 2.05" class="knee" />
<position name="left_ankle" joint="left_ankle" ctrlrange="-0.87 0.52" class="ankle" />
<position name="right_hip_yaw" joint="right_hip_yaw" ctrlrange="-0.43 0.43" class="hip" />
<position name="right_hip_roll" joint="right_hip_roll" ctrlrange="-0.43 0.43" class="hip" />
<position name="right_hip_pitch" joint="right_hip_pitch" ctrlrange="-3.14 2.53" class="hip" />
<position name="right_knee" joint="right_knee" ctrlrange="-0.26 2.05" class="knee" />
<position name="right_ankle" joint="right_ankle" ctrlrange="-0.87 0.52" class="ankle" />
<position name="torso" joint="torso" ctrlrange="-2.35 2.35" class="torso" />
<position name="left_shoulder_pitch" joint="left_shoulder_pitch" ctrlrange="-2.87 2.87" class="shoulder1" />
<position name="left_shoulder_roll" joint="left_shoulder_roll" ctrlrange="-0.34 3.11" class="shoulder1" />
<position name="left_shoulder_yaw" joint="left_shoulder_yaw" ctrlrange="-1.3 4.45" class="shoulder2" />
<position name="left_elbow" joint="left_elbow" ctrlrange="-1.25 2.61" class="elbow" />
<position name="right_shoulder_pitch" joint="right_shoulder_pitch" ctrlrange="-2.87 2.87" class="shoulder1" />
<position name="right_shoulder_roll" joint="right_shoulder_roll" ctrlrange="-3.11 0.34" class="shoulder1" />
<position name="right_shoulder_yaw" joint="right_shoulder_yaw" ctrlrange="-4.45 1.3" class="shoulder2" />
<position name="right_elbow" joint="right_elbow" ctrlrange="-1.25 2.61" class="elbow" />
</actuator>
<sensor>
<touch name="left_foot_sensor" site="left_foot"/>
<touch name="right_foot_sensor" site="right_foot"/>
</sensor>
</mujoco>