-
Notifications
You must be signed in to change notification settings - Fork 50
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
33e5bd9
commit a32be5a
Showing
3 changed files
with
241 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,220 @@ | ||
<mujoco model="humanoid"> | ||
|
||
<statistic extent="2" center="0 0 1"/> | ||
|
||
<option timestep="0.00555"/> | ||
|
||
<default> | ||
<motor ctrlrange="-1 1" ctrllimited="true"/> | ||
<default class="body"> | ||
<geom type="capsule" condim="1" friction="1.0 0.05 0.05" solimp=".9 .99 .003" solref=".015 1"/> | ||
<joint type="hinge" damping="0.1" stiffness="5" armature=".007" limited="true" solimplimit="0 .99 .01"/> | ||
<site size=".04" group="3"/> | ||
<default class="force-torque"> | ||
<site type="box" size=".01 .01 .02" rgba="1 0 0 1" /> | ||
</default> | ||
<default class="touch"> | ||
<site type="capsule" rgba="0 0 1 .3"/> | ||
</default> | ||
</default> | ||
</default> | ||
|
||
<worldbody> | ||
<geom name="floor" type="plane" conaffinity="1" size="100 100 .2" material="grid"/> | ||
<body name="pelvis" pos="0 0 1" childclass="body"> | ||
<freejoint name="root"/> | ||
<site name="root" class="force-torque"/> | ||
<geom name="pelvis" type="sphere" pos="0 0 0.07" size=".09" density="2226"/> | ||
<geom name="upper_waist" type="sphere" pos="0 0 0.205" size="0.07" density="2226"/> | ||
<site name="pelvis" class="touch" type="sphere" pos="0 0 0.07" size="0.091"/> | ||
<site name="upper_waist" class="touch" type="sphere" pos="0 0 0.205" size="0.071"/> | ||
|
||
<body name="torso" pos="0 0 0.236151"> | ||
<light name="top" pos="0 0 2" mode="trackcom"/> | ||
<camera name="back" pos="-3 0 1" xyaxes="0 -1 0 1 0 2" mode="trackcom"/> | ||
<camera name="side" pos="0 -3 1" xyaxes="1 0 0 0 1 2" mode="trackcom"/> | ||
<joint name="abdomen_x" pos="0 0 0" axis="1 0 0" range="-60 60" stiffness="600" damping="60" armature=".025"/> | ||
<joint name="abdomen_y" pos="0 0 0" axis="0 1 0" range="-60 90" stiffness="600" damping="60" armature=".025"/> | ||
<joint name="abdomen_z" pos="0 0 0" axis="0 0 1" range="-50 50" stiffness="600" damping="60" armature=".025"/> | ||
<geom name="torso" type="sphere" pos="0 0 0.12" size="0.11" density="1794"/> | ||
<site name="torso" class="touch" type="sphere" pos="0 0 0.12" size="0.111"/> | ||
|
||
<geom name="right_clavicle" fromto="-0.0060125 -0.0457775 0.2287955 -0.016835 -0.128177 0.2376182" size=".045" density="1100"/> | ||
<geom name="left_clavicle" fromto="-0.0060125 0.0457775 0.2287955 -0.016835 0.128177 0.2376182" size=".045" density="1100"/> | ||
|
||
<body name="head" pos="0 0 0.223894"> | ||
<joint name="neck_x" axis="1 0 0" range="-50 50" stiffness="50" damping="5" armature=".017"/> | ||
<joint name="neck_y" axis="0 1 0" range="-40 60" stiffness="50" damping="5" armature=".017"/> | ||
<joint name="neck_z" axis="0 0 1" range="-45 45" stiffness="50" damping="5" armature=".017"/> | ||
<geom name="head" type="sphere" pos="0 0 0.175" size="0.095" density="1081"/> | ||
<site name="head" class="touch" pos="0 0 0.175" type="sphere" size="0.103"/> | ||
<camera name="egocentric" pos=".103 0 0.175" xyaxes="0 -1 0 .1 0 1" fovy="80"/> | ||
</body> | ||
|
||
<body name="right_upper_arm" pos="-0.02405 -0.18311 0.24350"> | ||
<joint name="right_shoulder_x" axis="1 0 0" range="-180 45" stiffness="200" damping="20" armature=".02"/> | ||
<joint name="right_shoulder_y" axis="0 1 0" range="-180 60" stiffness="200" damping="20" armature=".02"/> | ||
<joint name="right_shoulder_z" axis="0 0 1" range="-90 90" stiffness="200" damping="20" armature=".02"/> | ||
<geom name="right_upper_arm" fromto="0 0 -0.05 0 0 -0.23" size=".045" density="982"/> | ||
<site name="right_upper_arm" class="touch" pos="0 0 -0.14" size="0.046 0.1" zaxis="0 0 1"/> | ||
|
||
<body name="right_lower_arm" pos="0 0 -0.274788"> | ||
<joint name="right_elbow" axis="0 1 0" range="-160 0" stiffness="150" damping="15" armature=".015"/> | ||
<geom name="right_lower_arm" fromto="0 0 -0.0525 0 0 -0.1875" size="0.04" density="1056"/> | ||
<site name="right_lower_arm" class="touch" pos="0 0 -0.12" size="0.041 0.0685" zaxis="0 1 0"/> | ||
|
||
<body name="right_hand" pos="0 0 -0.258947"> | ||
<joint name="right_hand_x" axis="1 0 0" range="-90 90" stiffness="100" damping="10" armature=".01"/> | ||
<joint name="right_hand_y" axis="0 1 0" range="-90 90" stiffness="100" damping="10" armature=".003"/> | ||
<joint name="right_hand_z" axis="0 0 1" range="-90 90" stiffness="100" damping="10" armature=".003"/> | ||
<geom name="right_hand" type="sphere" size=".04" density="1865"/> | ||
<site name="right_hand" class="touch" type="sphere" size=".041"/> | ||
</body> | ||
</body> | ||
</body> | ||
|
||
<body name="left_upper_arm" pos="-0.02405 0.18311 0.24350"> | ||
<joint name="left_shoulder_x" axis="1 0 0" range="-45 180" stiffness="200" damping="20" armature=".02"/> | ||
<joint name="left_shoulder_y" axis="0 1 0" range="-180 60" stiffness="200" damping="20" armature=".02"/> | ||
<joint name="left_shoulder_z" axis="0 0 1" range="-90 90" stiffness="200" damping="20" armature=".02"/> | ||
<geom name="left_upper_arm" fromto="0 0 -0.05 0 0 -0.23" size="0.045" density="982"/> | ||
<site name="left_upper_arm" class="touch" pos="0 0 -0.14" size="0.046 0.1" zaxis="0 0 1"/> | ||
|
||
<body name="left_lower_arm" pos="0 0 -0.274788"> | ||
<joint name="left_elbow" axis="0 1 0" range="-160 0" stiffness="150" damping="15" armature=".015"/> | ||
<geom name="left_lower_arm" fromto="0 0 -0.0525 0 0 -0.1875" size="0.04" density="1056"/> | ||
<site name="left_lower_arm" class="touch" pos="0 0 -0.1" size="0.041 0.0685" zaxis="0 0 1"/> | ||
|
||
<body name="left_hand" pos="0 0 -0.258947"> | ||
<joint name="left_hand_x" axis="1 0 0" range="-90 90" stiffness="100" damping="10" armature=".01"/> | ||
<joint name="left_hand_y" axis="0 1 0" range="-90 90" stiffness="100" damping="10" armature=".003"/> | ||
<joint name="left_hand_z" axis="0 0 1" range="-90 90" stiffness="100" damping="10" armature=".003"/> | ||
<geom name="left_hand" type="sphere" size=".04" density="1865"/> | ||
<site name="left_hand" class="touch" type="sphere" size=".041"/> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
|
||
<body name="right_thigh" pos="0 -0.084887 0"> | ||
<site name="right_hip" class="force-torque"/> | ||
<joint name="right_hip_x" axis="1 0 0" range="-60 15" stiffness="300" damping="30" armature=".02"/> | ||
<joint name="right_hip_y" axis="0 1 0" range="-140 60" stiffness="300" damping="30" armature=".02"/> | ||
<joint name="right_hip_z" axis="0 0 1" range="-60 35" stiffness="300" damping="30" armature=".02"/> | ||
<geom name="right_thigh" fromto="0 0 -0.06 0 0 -0.36" size="0.055" density="1269"/> | ||
<site name="right_thigh" class="touch" pos="0 0 -0.21" size="0.056 0.301" zaxis="0 0 -1"/> | ||
|
||
<body name="right_shin" pos="0 0 -0.421546"> | ||
<site name="right_knee" class="force-torque" pos="0 0 0"/> | ||
<joint name="right_knee" pos="0 0 0" axis="0 1 0" range="0 160" stiffness="300" damping="30" armature=".02"/> | ||
<geom name="right_shin" fromto="0 0 -0.045 0 0 -0.355" size=".05" density="1014"/> | ||
<site name="right_shin" class="touch" pos="0 0 -0.2" size="0.051 0.156" zaxis="0 0 -1"/> | ||
|
||
<body name="right_foot" pos="0 0 -0.409870"> | ||
<site name="right_ankle" class="force-torque"/> | ||
<joint name="right_ankle_x" pos="0 0 0" axis="1 0 0" range="-30 30" stiffness="200" damping="20" armature=".01"/> | ||
<joint name="right_ankle_y" pos="0 0 0" axis="0 1 0" range="-55 55" stiffness="200" damping="20" armature=".01"/> | ||
<joint name="right_ankle_z" pos="0 0 0" axis="0 0 1" range="-40 40" stiffness="200" damping="20" armature=".01"/> | ||
<geom name="right_foot" type="box" pos="0.045 0 -0.0225" size="0.0885 0.045 0.0275" density="1141"/> | ||
<site name="right_foot" class="touch" type="box" pos="0.045 0 -0.0225" size="0.0895 0.055 0.0285"/> | ||
</body> | ||
</body> | ||
</body> | ||
|
||
<body name="left_thigh" pos="0 0.084887 0"> | ||
<site name="left_hip" class="force-torque"/> | ||
<joint name="left_hip_x" axis="1 0 0" range="-15 60" stiffness="300" damping="30" armature=".02"/> | ||
<joint name="left_hip_y" axis="0 1 0" range="-140 60" stiffness="300" damping="30" armature=".02"/> | ||
<joint name="left_hip_z" axis="0 0 1" range="-35 60" stiffness="300" damping="30" armature=".02"/> | ||
<geom name="left_thigh" fromto="0 0 -0.06 0 0 -0.36" size=".055" density="1269"/> | ||
<site name="left_thigh" class="touch" pos="0 0 -0.21" size="0.056 0.301" zaxis="0 0 -1"/> | ||
|
||
<body name="left_shin" pos="0 0 -0.421546"> | ||
<site name="left_knee" class="force-torque" pos="0 0 .02"/> | ||
<joint name="left_knee" pos="0 0 0" axis="0 1 0" range="0 160" stiffness="300" damping="30" armature=".02"/> | ||
<geom name="left_shin" fromto="0 0 -0.045 0 0 -0.355" size=".05" density="1014"/> | ||
<site name="left_shin" class="touch" pos="0 0 -0.2" size="0.051 0.156" zaxis="0 0 -1"/> | ||
|
||
<body name="left_foot" pos="0 0 -0.409870"> | ||
<site name="left_ankle" class="force-torque"/> | ||
<joint name="left_ankle_x" pos="0 0 0" axis="1 0 0" range="-30 30" stiffness="200" damping="20" armature=".01"/> | ||
<joint name="left_ankle_y" pos="0 0 0" axis="0 1 0" range="-55 55" stiffness="200" damping="20" armature=".01"/> | ||
<joint name="left_ankle_z" pos="0 0 0" axis="0 0 1" range="-40 40" stiffness="200" damping="20" armature=".01"/> | ||
<geom name="left_foot" type="box" pos="0.045 0 -0.0225" size="0.0885 0.045 0.0275" density="1141"/> | ||
<site name="left_foot" class="touch" type="box" pos="0.045 0 -0.0225" size="0.0895 0.055 0.0285"/> | ||
</body> | ||
</body> | ||
</body> | ||
</body> | ||
</worldbody> | ||
|
||
<actuator> | ||
<motor name='abdomen_x' gear='125' joint='abdomen_x'/> | ||
<motor name='abdomen_y' gear='125' joint='abdomen_y'/> | ||
<motor name='abdomen_z' gear='125' joint='abdomen_z'/> | ||
<motor name='neck_x' gear='20' joint='neck_x'/> | ||
<motor name='neck_y' gear='20' joint='neck_y'/> | ||
<motor name='neck_z' gear='20' joint='neck_z'/> | ||
<motor name='right_shoulder_x' gear='70' joint='right_shoulder_x'/> | ||
<motor name='right_shoulder_y' gear='70' joint='right_shoulder_y'/> | ||
<motor name='right_shoulder_z' gear='70' joint='right_shoulder_z'/> | ||
<motor name='right_elbow' gear='60' joint='right_elbow'/> | ||
<motor name='left_shoulder_x' gear='70' joint='left_shoulder_x'/> | ||
<motor name='left_shoulder_y' gear='70' joint='left_shoulder_y'/> | ||
<motor name='left_shoulder_z' gear='70' joint='left_shoulder_z'/> | ||
<motor name='left_elbow' gear='60' joint='left_elbow'/> | ||
<motor name='right_hip_x' gear='125' joint='right_hip_x'/> | ||
<motor name='right_hip_z' gear='125' joint='right_hip_z'/> | ||
<motor name='right_hip_y' gear='125' joint='right_hip_y'/> | ||
<motor name='right_knee' gear='100' joint='right_knee'/> | ||
<motor name='right_ankle_x' gear='50' joint='right_ankle_x'/> | ||
<motor name='right_ankle_y' gear='50' joint='right_ankle_y'/> | ||
<motor name='right_ankle_z' gear='50' joint='right_ankle_z'/> | ||
<motor name='left_hip_x' gear='125' joint='left_hip_x'/> | ||
<motor name='left_hip_z' gear='125' joint='left_hip_z'/> | ||
<motor name='left_hip_y' gear='125' joint='left_hip_y'/> | ||
<motor name='left_knee' gear='100' joint='left_knee'/> | ||
<motor name='left_ankle_x' gear='50' joint='left_ankle_x'/> | ||
<motor name='left_ankle_y' gear='50' joint='left_ankle_y'/> | ||
<motor name='left_ankle_z' gear='50' joint='left_ankle_z'/> | ||
</actuator> | ||
|
||
<sensor> | ||
<subtreelinvel name="pelvis_subtreelinvel" body="pelvis"/> | ||
<accelerometer name="root_accel" site="root"/> | ||
<velocimeter name="root_vel" site="root"/> | ||
<gyro name="root_gyro" site="root"/> | ||
|
||
<force name="left_ankle_force" site="left_ankle"/> | ||
<force name="right_ankle_force" site="right_ankle"/> | ||
<force name="left_knee_force" site="left_knee"/> | ||
<force name="right_knee_force" site="right_knee"/> | ||
<force name="left_hip_force" site="left_hip"/> | ||
<force name="right_hip_force" site="right_hip"/> | ||
|
||
<torque name="left_ankle_torque" site="left_ankle"/> | ||
<torque name="right_ankle_torque" site="right_ankle"/> | ||
<torque name="left_knee_torque" site="left_knee"/> | ||
<torque name="right_knee_torque" site="right_knee"/> | ||
<torque name="left_hip_torque" site="left_hip"/> | ||
<torque name="right_hip_torque" site="right_hip"/> | ||
|
||
<touch name="pelvis_touch" site="pelvis"/> | ||
<touch name="upper_waist_touch" site="upper_waist"/> | ||
<touch name="torso_touch" site="torso"/> | ||
<touch name="head_touch" site="head"/> | ||
<touch name="right_upper_arm_touch" site="right_upper_arm"/> | ||
<touch name="right_lower_arm_touch" site="right_lower_arm"/> | ||
<touch name="right_hand_touch" site="right_hand"/> | ||
<touch name="left_upper_arm_touch" site="left_upper_arm"/> | ||
<touch name="left_lower_arm_touch" site="left_lower_arm"/> | ||
<touch name="left_hand_touch" site="left_hand"/> | ||
<touch name="right_thigh_touch" site="right_thigh"/> | ||
<touch name="right_shin_touch" site="right_shin"/> | ||
<touch name="right_foot_touch" site="right_foot"/> | ||
<touch name="left_thigh_touch" site="left_thigh"/> | ||
<touch name="left_shin_touch" site="left_shin"/> | ||
<touch name="left_foot_touch" site="left_foot"/> | ||
</sensor> | ||
|
||
</mujoco> |