| <mujoco model='humanoid'> | |
| <compiler inertiafromgeom='true' angle='degree'/> | |
| <default> | |
| <joint limited='true' damping='1' armature='0' /> | |
| <geom contype='1' conaffinity='1' condim='1' rgba='0.8 0.6 .4 1' | |
| margin="0.001" solref=".02 1" solimp=".8 .8 .01" material="geom"/> | |
| <motor ctrlrange='-.4 .4' ctrllimited='true'/> | |
| </default> | |
| <option timestep='0.002' iterations="50" solver="PGS"> | |
| <flag energy="enable"/> | |
| </option> | |
| <visual> | |
| <map fogstart="3" fogend="5" force="0.1"/> | |
| <quality shadowsize="2048"/> | |
| </visual> | |
| <asset> | |
| <texture type="skybox" builtin="gradient" width="100" height="100" rgb1=".4 .6 .8" | |
| rgb2="0 0 0"/> | |
| <texture name="texgeom" type="cube" builtin="flat" mark="cross" width="127" height="1278" | |
| rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" random="0.01"/> | |
| <texture name="texplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2" | |
| width="100" height="100"/> | |
| <material name='MatPlane' reflectance='0.5' texture="texplane" texrepeat="1 1" texuniform="true"/> | |
| <material name='geom' texture="texgeom" texuniform="true"/> | |
| </asset> | |
| <worldbody> | |
| <geom name='floor' pos='0 0 0' size='10 10 0.125' type='plane' material="MatPlane" condim='3'/> | |
| <body name='torso' pos='0 0 1.4'> | |
| <light mode='trackcom' directional='false' diffuse='.8 .8 .8' specular='0.3 0.3 0.3' pos='0 0 4.0' dir='0 0 -1'/> | |
| <geom name='torso1' type='capsule' fromto='0 -.07 0 0 .07 0' size='0.07' /> | |
| <geom name='head' type='sphere' pos='0 0 .19' size='.09'/> | |
| <geom name='uwaist' type='capsule' fromto='-.01 -.06 -.12 -.01 .06 -.12' size='0.06'/> | |
| <body name='lwaist' pos='-.01 0 -0.260' quat='1.000 0 -0.002 0' > | |
| <geom name='lwaist' type='capsule' fromto='0 -.06 0 0 .06 0' size='0.06' /> | |
| <joint name='abdomen_z' type='hinge' pos='0 0 0.065' axis='0 0 1' range='-45 45' damping='5' stiffness='20' armature='0.02' /> | |
| <joint name='abdomen_y' type='hinge' pos='0 0 0.065' axis='0 1 0' range='-75 30' damping='5' stiffness='10' armature='0.02' /> | |
| <body name='pelvis' pos='0 0 -0.165' quat='1.000 0 -0.002 0' > | |
| <joint name='abdomen_x' type='hinge' pos='0 0 0.1' axis='1 0 0' range='-35 35' damping='5' stiffness='10' armature='0.02' /> | |
| <geom name='butt' type='capsule' fromto='-.02 -.07 0 -.02 .07 0' size='0.09' /> | |
| <body name='right_thigh' pos='0 -0.1 -0.04' > | |
| <joint name='right_hip_x' type='hinge' pos='0 0 0' axis='1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' /> | |
| <joint name='right_hip_z' type='hinge' pos='0 0 0' axis='0 0 1' range='-60 35' damping='5' stiffness='10' armature='0.01' /> | |
| <joint name='right_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-110 20' damping='5' stiffness='20' armature='0.0080' /> | |
| <geom name='right_thigh1' type='capsule' fromto='0 0 0 0 0.01 -.34' size='0.06' /> | |
| <body name='right_shin' pos='0 0.01 -0.403' > | |
| <joint name='right_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' armature='0.0060' /> | |
| <geom name='right_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' /> | |
| <body name='right_foot' pos='0 0 -.39' > | |
| <joint name='right_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' /> | |
| <joint name='right_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' /> | |
| <geom name='right_foot_cap1' type='capsule' fromto='-.07 -0.02 0 0.14 -0.04 0' size='0.027' /> | |
| <geom name='right_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 0.02 0' size='0.027' /> | |
| </body> | |
| </body> | |
| </body> | |
| <body name='left_thigh' pos='0 0.1 -0.04' > | |
| <joint name='left_hip_x' type='hinge' pos='0 0 0' axis='-1 0 0' range='-25 5' damping='5' stiffness='10' armature='0.01' /> | |
| <joint name='left_hip_z' type='hinge' pos='0 0 0' axis='0 0 -1' range='-60 35' damping='5' stiffness='10' armature='0.01' /> | |
| <joint name='left_hip_y' type='hinge' pos='0 0 0' axis='0 1 0' range='-120 20' damping='5' stiffness='20' armature='0.01' /> | |
| <geom name='left_thigh1' type='capsule' fromto='0 0 0 0 -0.01 -.34' size='0.06' /> | |
| <body name='left_shin' pos='0 -0.01 -0.403' > | |
| <joint name='left_knee' type='hinge' pos='0 0 .02' axis='0 -1 0' range='-160 -2' stiffness='1' armature='0.0060' /> | |
| <geom name='left_shin1' type='capsule' fromto='0 0 0 0 0 -.3' size='0.049' /> | |
| <body name='left_foot' pos='0 0 -.39' > | |
| <joint name='left_ankle_y' type='hinge' pos='0 0 0.08' axis='0 1 0' range='-50 50' stiffness='4' armature='0.0008' /> | |
| <joint name='left_ankle_x' type='hinge' pos='0 0 0.04' axis='1 0 0.5' range='-50 50' stiffness='1' armature='0.0006' /> | |
| <geom name='left_foot_cap1' type='capsule' fromto='-.07 0.02 0 0.14 0.04 0' size='0.027' /> | |
| <geom name='left_foot_cap2' type='capsule' fromto='-.07 0 0 0.14 -0.02 0' size='0.027' /> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| </body> | |
| <body name='right_upper_arm' pos='0 -0.17 0.06' > | |
| <joint name='right_shoulder1' type='hinge' pos='0 0 0' axis='2 1 1' range='-85 60' stiffness='1' armature='0.0068' /> | |
| <joint name='right_shoulder2' type='hinge' pos='0 0 0' axis='0 -1 1' range='-85 60' stiffness='1' armature='0.0051' /> | |
| <geom name='right_uarm1' type='capsule' fromto='0 0 0 .16 -.16 -.16' size='0.04 0.16' /> | |
| <body name='right_lower_arm' pos='.18 -.18 -.18' > | |
| <joint name='right_elbow' type='hinge' pos='0 0 0' axis='0 -1 1' range='-90 50' stiffness='0' armature='0.0028' /> | |
| <geom name='right_larm' type='capsule' fromto='0.01 0.01 0.01 .17 .17 .17' size='0.031' /> | |
| <geom name='right_hand' type='sphere' pos='.18 .18 .18' size='0.04'/> | |
| </body> | |
| </body> | |
| <body name='left_upper_arm' pos='0 0.17 0.06' > | |
| <joint name='left_shoulder1' type='hinge' pos='0 0 0' axis='2 -1 1' range='-60 85' stiffness='1' armature='0.0068' /> | |
| <joint name='left_shoulder2' type='hinge' pos='0 0 0' axis='0 1 1' range='-60 85' stiffness='1' armature='0.0051' /> | |
| <geom name='left_uarm1' type='capsule' fromto='0 0 0 .16 .16 -.16' size='0.04 0.16' /> | |
| <body name='left_lower_arm' pos='.18 .18 -.18' > | |
| <joint name='left_elbow' type='hinge' pos='0 0 0' axis='0 -1 -1' range='-90 50' stiffness='0' armature='0.0028' /> | |
| <geom name='left_larm' type='capsule' fromto='0.01 -0.01 0.01 .17 -.17 .17' size='0.031' /> | |
| <geom name='left_hand' type='sphere' pos='.18 -.18 .18' size='0.04'/> | |
| </body> | |
| </body> | |
| </body> | |
| </worldbody> | |
| <actuator> | |
| <motor name='abdomen_y' gear='200' joint='abdomen_y' /> | |
| <motor name='abdomen_z' gear='200' joint='abdomen_z' /> | |
| <motor name='abdomen_x' gear='200' joint='abdomen_x' /> | |
| <motor name='right_hip_x' gear='200' joint='right_hip_x' /> | |
| <motor name='right_hip_z' gear='200' joint='right_hip_z' /> | |
| <motor name='right_hip_y' gear='600' joint='right_hip_y' /> | |
| <motor name='right_knee' gear='400' joint='right_knee' /> | |
| <motor name='right_ankle_x' gear='100' joint='right_ankle_x' /> | |
| <motor name='right_ankle_y' gear='100' joint='right_ankle_y' /> | |
| <motor name='left_hip_x' gear='200' joint='left_hip_x' /> | |
| <motor name='left_hip_z' gear='200' joint='left_hip_z' /> | |
| <motor name='left_hip_y' gear='600' joint='left_hip_y' /> | |
| <motor name='left_knee' gear='400' joint='left_knee' /> | |
| <motor name='left_ankle_x' gear='100' joint='left_ankle_x' /> | |
| <motor name='left_ankle_y' gear='100' joint='left_ankle_y' /> | |
| <motor name='right_shoulder1' gear='100' joint='right_shoulder1' /> | |
| <motor name='right_shoulder2' gear='100' joint='right_shoulder2' /> | |
| <motor name='right_elbow' gear='200' joint='right_elbow' /> | |
| <motor name='left_shoulder1' gear='100' joint='left_shoulder1' /> | |
| <motor name='left_shoulder2' gear='100' joint='left_shoulder2' /> | |
| <motor name='left_elbow' gear='200' joint='left_elbow' /> | |
| </actuator> | |
| </mujoco> | |