Spaces:
Running
Running
<mujoco model="humanoidstandup"> | |
<compiler angle="degree" inertiafromgeom="true"/> | |
<default> | |
<joint armature="1" damping="1" limited="true"/> | |
<geom conaffinity="1" condim="1" contype="1" margin="0.001" material="geom" rgba="0.8 0.6 .4 1"/> | |
<motor ctrllimited="true" ctrlrange="-.4 .4"/> | |
</default> | |
<option integrator="RK4" iterations="50" solver="PGS" timestep="0.003"> | |
<!-- <flags solverstat="enable" energy="enable"/>--> | |
</option> | |
<size nkey="5" nuser_geom="1"/> | |
<visual> | |
<map fogend="5" fogstart="3"/> | |
</visual> | |
<asset> | |
<texture builtin="gradient" height="100" rgb1=".4 .5 .6" rgb2="0 0 0" type="skybox" width="100"/> | |
<!-- <texture builtin="gradient" height="100" rgb1="1 1 1" rgb2="0 0 0" type="skybox" width="100"/>--> | |
<texture builtin="flat" height="1278" mark="cross" markrgb="1 1 1" name="texgeom" random="0.01" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" type="cube" width="127"/> | |
<texture builtin="checker" height="100" name="texplane" rgb1="0 0 0" rgb2="0.8 0.8 0.8" type="2d" width="100"/> | |
<material name="MatPlane" reflectance="0.5" shininess="1" specular="1" texrepeat="60 60" texture="texplane"/> | |
<material name="geom" texture="texgeom" texuniform="true"/> | |
</asset> | |
<worldbody> | |
<light cutoff="100" diffuse="1 1 1" dir="-0 0 -1.3" directional="true" exponent="1" pos="0 0 1.3" specular=".1 .1 .1"/> | |
<geom condim="3" friction="1 .1 .1" material="MatPlane" name="floor" pos="0 0 0" rgba="0.8 0.9 0.8 1" size="20 20 0.125" type="plane"/> | |
<!-- <geom condim="3" material="MatPlane" name="floor" pos="0 0 0" size="10 10 0.125" type="plane"/>--> | |
<body name="torso" pos="0 0 .105"> | |
<camera name="track" mode="trackcom" pos="0 -3 .5" xyaxes="1 0 0 0 0 1"/> | |
<joint armature="0" damping="0" limited="false" name="root" pos="0 0 0" stiffness="0" type="free"/> | |
<geom fromto="0 -.07 0 0 .07 0" name="torso1" size="0.07" type="capsule"/> | |
<geom name="head" pos="-.15 0 0" size=".09" type="sphere" user="258"/> | |
<geom fromto=".11 -.06 0 .11 .06 0" name="uwaist" size="0.06" type="capsule"/> | |
<body name="lwaist" pos=".21 0 0" quat="1.000 0 -0.002 0"> | |
<geom fromto="0 -.06 0 0 .06 0" name="lwaist" size="0.06" type="capsule"/> | |
<joint armature="0.02" axis="0 0 1" damping="5" name="abdomen_z" pos="0 0 0.065" range="-45 45" stiffness="20" type="hinge"/> | |
<joint armature="0.02" axis="0 1 0" damping="5" name="abdomen_y" pos="0 0 0.065" range="-75 30" stiffness="10" type="hinge"/> | |
<body name="pelvis" pos="0.165 0 0" quat="1.000 0 -0.002 0"> | |
<joint armature="0.02" axis="1 0 0" damping="5" name="abdomen_x" pos="0 0 0.1" range="-35 35" stiffness="10" type="hinge"/> | |
<geom fromto="-.02 -.07 0 -.02 .07 0" name="butt" size="0.09" type="capsule"/> | |
<body name="right_thigh" pos="0 -0.1 0"> | |
<joint armature="0.01" axis="1 0 0" damping="5" name="right_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/> | |
<joint armature="0.01" axis="0 0 1" damping="5" name="right_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/> | |
<joint armature="0.0080" axis="0 1 0" damping="5" name="right_hip_y" pos="0 0 0" range="-110 20" stiffness="20" type="hinge"/> | |
<geom fromto="0 0 0 0.34 0.01 0" name="right_thigh1" size="0.06" type="capsule"/> | |
<body name="right_shin" pos="0.403 0.01 0"> | |
<joint armature="0.0060" axis="0 -1 0" name="right_knee" pos="0 0 .02" range="-160 -2" type="hinge"/> | |
<geom fromto="0 0 0 0.3 0 0" name="right_shin1" size="0.049" type="capsule"/> | |
<body name="right_foot" pos="0.35 0 -.10"> | |
<geom name="right_foot" pos="0 0 0.1" size="0.075" type="sphere" user="0"/> | |
</body> | |
</body> | |
</body> | |
<body name="left_thigh" pos="0 0.1 0"> | |
<joint armature="0.01" axis="-1 0 0" damping="5" name="left_hip_x" pos="0 0 0" range="-25 5" stiffness="10" type="hinge"/> | |
<joint armature="0.01" axis="0 0 -1" damping="5" name="left_hip_z" pos="0 0 0" range="-60 35" stiffness="10" type="hinge"/> | |
<joint armature="0.01" axis="0 1 0" damping="5" name="left_hip_y" pos="0 0 0" range="-120 20" stiffness="20" type="hinge"/> | |
<geom fromto="0 0 0 0.34 -0.01 0" name="left_thigh1" size="0.06" type="capsule"/> | |
<body name="left_shin" pos="0.403 -0.01 0"> | |
<joint armature="0.0060" axis="0 -1 0" name="left_knee" pos="0 0 .02" range="-160 -2" stiffness="1" type="hinge"/> | |
<geom fromto="0 0 0 0.3 0 0" name="left_shin1" size="0.049" type="capsule"/> | |
<body name="left_foot" pos="0.35 0 -.1"> | |
<geom name="left_foot" type="sphere" size="0.075" pos="0 0 0.1" user="0" /> | |
</body> | |
</body> | |
</body> | |
</body> | |
</body> | |
<body name="right_upper_arm" pos="0 -0.17 0.06"> | |
<joint armature="0.0068" axis="2 1 1" name="right_shoulder1" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/> | |
<joint armature="0.0051" axis="0 -1 1" name="right_shoulder2" pos="0 0 0" range="-85 60" stiffness="1" type="hinge"/> | |
<geom fromto="0 0 0 .16 -.16 -.16" name="right_uarm1" size="0.04 0.16" type="capsule"/> | |
<body name="right_lower_arm" pos=".18 -.18 -.18"> | |
<joint armature="0.0028" axis="0 -1 1" name="right_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/> | |
<geom fromto="0.01 0.01 0.01 .17 .17 .17" name="right_larm" size="0.031" type="capsule"/> | |
<geom name="right_hand" pos=".18 .18 .18" size="0.04" type="sphere"/> | |
<camera pos="0 0 0"/> | |
</body> | |
</body> | |
<body name="left_upper_arm" pos="0 0.17 0.06"> | |
<joint armature="0.0068" axis="2 -1 1" name="left_shoulder1" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/> | |
<joint armature="0.0051" axis="0 1 1" name="left_shoulder2" pos="0 0 0" range="-60 85" stiffness="1" type="hinge"/> | |
<geom fromto="0 0 0 .16 .16 -.16" name="left_uarm1" size="0.04 0.16" type="capsule"/> | |
<body name="left_lower_arm" pos=".18 .18 -.18"> | |
<joint armature="0.0028" axis="0 -1 -1" name="left_elbow" pos="0 0 0" range="-90 50" stiffness="0" type="hinge"/> | |
<geom fromto="0.01 -0.01 0.01 .17 -.17 .17" name="left_larm" size="0.031" type="capsule"/> | |
<geom name="left_hand" pos=".18 -.18 .18" size="0.04" type="sphere"/> | |
</body> | |
</body> | |
</body> | |
</worldbody> | |
<tendon> | |
<fixed name="left_hipknee"> | |
<joint coef="-1" joint="left_hip_y"/> | |
<joint coef="1" joint="left_knee"/> | |
</fixed> | |
<fixed name="right_hipknee"> | |
<joint coef="-1" joint="right_hip_y"/> | |
<joint coef="1" joint="right_knee"/> | |
</fixed> | |
</tendon> | |
<actuator> | |
<motor gear="100" joint="abdomen_y" name="abdomen_y"/> | |
<motor gear="100" joint="abdomen_z" name="abdomen_z"/> | |
<motor gear="100" joint="abdomen_x" name="abdomen_x"/> | |
<motor gear="100" joint="right_hip_x" name="right_hip_x"/> | |
<motor gear="100" joint="right_hip_z" name="right_hip_z"/> | |
<motor gear="300" joint="right_hip_y" name="right_hip_y"/> | |
<motor gear="200" joint="right_knee" name="right_knee"/> | |
<motor gear="100" joint="left_hip_x" name="left_hip_x"/> | |
<motor gear="100" joint="left_hip_z" name="left_hip_z"/> | |
<motor gear="300" joint="left_hip_y" name="left_hip_y"/> | |
<motor gear="200" joint="left_knee" name="left_knee"/> | |
<motor gear="25" joint="right_shoulder1" name="right_shoulder1"/> | |
<motor gear="25" joint="right_shoulder2" name="right_shoulder2"/> | |
<motor gear="25" joint="right_elbow" name="right_elbow"/> | |
<motor gear="25" joint="left_shoulder1" name="left_shoulder1"/> | |
<motor gear="25" joint="left_shoulder2" name="left_shoulder2"/> | |
<motor gear="25" joint="left_elbow" name="left_elbow"/> | |
</actuator> | |
</mujoco> | |