|
|
<mujoco model="go2_description">
|
|
|
<compiler angle="radian" meshdir="assets/"/>
|
|
|
|
|
|
<asset>
|
|
|
<mesh name="base_0" file="base_0.obj"/>
|
|
|
<mesh name="base_1" file="base_1.obj"/>
|
|
|
<mesh name="base_2" file="base_2.obj"/>
|
|
|
<mesh name="base_3" file="base_3.obj"/>
|
|
|
<mesh name="base_4" file="base_4.obj"/>
|
|
|
<mesh name="hip_0" file="hip_0.obj"/>
|
|
|
<mesh name="hip_1" file="hip_1.obj"/>
|
|
|
<mesh name="thigh_0" file="thigh_0.obj"/>
|
|
|
<mesh name="thigh_1" file="thigh_1.obj"/>
|
|
|
<mesh name="thigh_mirror_0" file="thigh_mirror_0.obj"/>
|
|
|
<mesh name="thigh_mirror_1" file="thigh_mirror_1.obj"/>
|
|
|
<mesh name="calf_0" file="calf_0.obj"/>
|
|
|
<mesh name="calf_1" file="calf_1.obj"/>
|
|
|
<mesh name="calf_mirror_0" file="calf_mirror_0.obj"/>
|
|
|
<mesh name="calf_mirror_1" file="calf_mirror_1.obj"/>
|
|
|
<mesh name="foot" file="foot.obj"/>
|
|
|
</asset>
|
|
|
|
|
|
<default>
|
|
|
<geom contype="1" conaffinity="1" friction="0.6 0.3 0.3" rgba="0.5 0.6 0.7 1" margin="0.001" group="0"/>
|
|
|
<motor ctrlrange="-33.5 33.5" ctrllimited="true"/>
|
|
|
<joint frictionloss="0.2" />
|
|
|
</default>
|
|
|
|
|
|
<worldbody>
|
|
|
<body name="base" pos="0 0 0">
|
|
|
<freejoint name="root"/>
|
|
|
<inertial pos="0.021112 0 -0.00536" mass="6.921" fullinertia="0.02448 0.098077 0.107 0.00012166 0.0014849 -3.12E-05"/>
|
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" mesh="base_0" rgba="0 0 0 1" />
|
|
|
<geom mesh="base_0" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="base_1" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="base_2" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="base_3" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="base_4" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom size="0.1881 0.04675 0.057" type="box" rgba="1 1 1 1"/>
|
|
|
<geom size="0.05 0.045" pos="0.285 0 0.01" type="cylinder"/>
|
|
|
<geom size="0.047" pos="0.293 0 -0.06"/>
|
|
|
|
|
|
<body name="FL_hip" pos="0.1934 0.0465 0">
|
|
|
<inertial pos="-0.0054 0.00194 -0.000105" quat="0.497014 0.499245 0.505462 0.498237" mass="0.678" diaginertia="0.00088403 0.000596003 0.000479967"/>
|
|
|
<joint name="FL_hip_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.0472 1.0472" limited="true" actuatorfrcrange="-0.9472 0.9472" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="hip_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="hip_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom size="0.046 0.02" pos="0 0.08 0" quat="1 1 0 0" type="cylinder"/>
|
|
|
<geom size="0.046 0.02" pos="0 0.08 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="FL_thigh" pos="0 0.0955 0">
|
|
|
<inertial pos="-0.00374 -0.0223 -0.0327" quat="0.829533 0.0847635 -0.0200632 0.551623" mass="1.152" diaginertia="0.00594973 0.00584149 0.000878787"/>
|
|
|
<joint name="FL_thigh_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-1.5708 3.4907" limited="true" actuatorfrcrange="-1.5708 3.4907" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="thigh_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="thigh_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom size="0.055 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="FL_calf" pos="0 0 -0.213">
|
|
|
<inertial pos="0.00629595 -0.000622121 -0.141417" quat="0.710672 0.00154099 -0.00450087 0.703508" mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
|
|
|
<joint name="FL_calf_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.7227 -0.83776" limited="true" actuatorfrcrange="-45.43 45.43" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="calf_0" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="calf_1" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom pos="0 0 -0.213" mesh="foot" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1"/>
|
|
|
<geom size="0.012 0.06" pos="0.008 0 -0.06" quat="0.994493 0 -0.104807 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder"/>
|
|
|
<geom size="0.0155 0.015" pos="0.00801333 0 -0.18745" quat="0.965093 0 0.261909 0" type="cylinder"/>
|
|
|
|
|
|
<body name="FL_foot" pos="0 0 -0.213">
|
|
|
<geom size="0.022" pos="0 0 0" rgba="0 0 0 1" friction="0.8 0.02 0.01" type="sphere"/>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
|
|
|
<body name="FR_hip" pos="0.1934 -0.0465 0">
|
|
|
<inertial pos="-0.0054 -0.00194 -0.000105" quat="0.498237 0.505462 0.499245 0.497014" mass="0.678" diaginertia="0.00088403 0.000596003 0.000479967"/>
|
|
|
<joint name="FR_hip_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.0472 1.0472" limited="true" actuatorfrcrange="-0.9472 0.9472" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="hip_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" quat="4.63268e-05 1 0 0"/>
|
|
|
<geom mesh="hip_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" quat="4.63268e-05 1 0 0" />
|
|
|
<geom size="0.046 0.02" pos="0 -0.08 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="FR_thigh" pos="0 -0.0955 0">
|
|
|
<inertial pos="-0.00374 0.0223 -0.0327" quat="0.551623 -0.0200632 0.0847635 0.829533" mass="1.152" diaginertia="0.00594973 0.00584149 0.000878787" />
|
|
|
<joint name="FR_thigh_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-1.5708 3.4907" limited="true" actuatorfrcrange="-1.5708 3.4907" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="thigh_mirror_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="thigh_mirror_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom size="0.055 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="FR_calf" pos="0 0 -0.213">
|
|
|
<inertial pos="0.00629595 0.000622121 -0.141417" quat="0.703508 -0.00450087 0.00154099 0.710672" mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
|
|
|
<joint name="FR_calf_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.7227 -0.83776" limited="true" actuatorfrcrange="-45.43 45.43" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="calf_mirror_0" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="calf_mirror_1" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom pos="0 0 -0.213" mesh="foot" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1"/>
|
|
|
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder"/>
|
|
|
<geom size="0.0155 0.015" pos="0.00801333 0 -0.18745" quat="0.965093 0 0.261909 0" type="cylinder"/>
|
|
|
|
|
|
<body name="FR_foot" pos="0 0 -0.213">
|
|
|
<geom size="0.022" pos="0 0 0" rgba="0 0 0 1" friction="0.8 0.02 0.01" type="sphere" />
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
|
|
|
<body name="RL_hip" pos="-0.1934 0.0465 0">
|
|
|
<inertial pos="0.0054 0.00194 -0.000105" quat="0.505462 0.498237 0.497014 0.499245" mass="0.678" diaginertia="0.00088403 0.000596003 0.000479967"/>
|
|
|
<joint name="RL_hip_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.0472 1.0472" limited="true" actuatorfrcrange="-0.9472 0.9472" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="hip_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" quat="4.63268e-05 0 1 0"/>
|
|
|
<geom mesh="hip_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" quat="4.63268e-05 0 1 0"/>
|
|
|
<geom size="0.046 0.02" pos="0 0.08 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="RL_thigh" pos="0 0.0955 0">
|
|
|
<inertial pos="-0.00374 -0.0223 -0.0327" quat="0.829533 0.0847635 -0.0200632 0.551623" mass="1.152" diaginertia="0.00594973 0.00584149 0.000878787"/>
|
|
|
<joint name="RL_thigh_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.5236 4.5379" limited="true" actuatorfrcrange="-0.5236 4.5379" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="thigh_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="thigh_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom size="0.055 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="RL_calf" pos="0 0 -0.213">
|
|
|
<inertial pos="0.00629595 -0.000622121 -0.141417" quat="0.710672 0.00154099 -0.00450087 0.703508" mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
|
|
|
<joint name="RL_calf_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.7227 -0.83776" limited="true" actuatorfrcrange="-45.43 45.43" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="calf_0" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="calf_1" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom pos="0 0 -0.213" mesh="foot" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1"/>
|
|
|
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder"/>
|
|
|
<geom size="0.0155 0.015" pos="0.00801333 0 -0.18745" quat="0.965093 0 0.261909 0" type="cylinder"/>
|
|
|
|
|
|
<body name="RL_foot" pos="0 0 -0.213">
|
|
|
<geom size="0.022" pos="0 0 0" rgba="0 0 0 1" friction="0.8 0.02 0.01" type="sphere"/>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
|
|
|
<body name="RR_hip" pos="-0.1934 -0.0465 0">
|
|
|
<inertial pos="0.0054 -0.00194 -0.000105" quat="0.499245 0.497014 0.498237 0.505462" mass="0.678" diaginertia="0.00088403 0.000596003 0.000479967"/>
|
|
|
<joint name="RR_hip_joint" type="hinge" pos="0 0 0" axis="1 0 0" range="-1.0472 1.0472" limited="true" actuatorfrcrange="-0.9472 0.9472" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="hip_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" quat="2.14617e-09 4.63268e-05 4.63268e-05 -1"/>
|
|
|
<geom mesh="hip_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" quat="2.14617e-09 4.63268e-05 4.63268e-05 -1"/>
|
|
|
<geom size="0.046 0.02" pos="0 -0.08 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="RR_thigh" pos="0 -0.0955 0">
|
|
|
<inertial pos="-0.00374 0.0223 -0.0327" quat="0.551623 -0.0200632 0.0847635 0.829533" mass="1.152" diaginertia="0.00594973 0.00584149 0.000878787"/>
|
|
|
<joint name="RR_thigh_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-0.5236 4.5379" limited="true" actuatorfrcrange="-0.5236 4.5379" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="thigh_mirror_0" rgba=".9 .95 .95 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="thigh_mirror_1" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom size="0.055 0.01225 0.017" pos="0 0 -0.1065" quat="0.707107 0 0.707107 0" type="box" rgba="1 1 1 1"/>
|
|
|
|
|
|
<body name="RR_calf" pos="0 0 -0.213">
|
|
|
<inertial pos="0.00629595 0.000622121 -0.141417" quat="0.703508 -0.00450087 0.00154099 0.710672" mass="0.241352" diaginertia="0.0014901 0.00146356 5.31397e-05"/>
|
|
|
<joint name="RR_calf_joint" type="hinge" pos="0 0 0" axis="0 1 0" range="-2.7227 -0.83776" limited="true" actuatorfrcrange="-45.43 45.43" stiffness="15" damping="2" armature="0.01"/>
|
|
|
<geom mesh="calf_mirror_0" rgba="0.671705 0.692426 0.774270 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom mesh="calf_mirror_1" rgba="0 0 0 1" type="mesh" contype="0" conaffinity="0" group="1" density="0" />
|
|
|
<geom pos="0 0 -0.213" mesh="foot" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0 0 0 1"/>
|
|
|
<geom size="0.013 0.06" pos="0.01 0 -0.06" quat="0.995004 0 -0.0998334 0" type="cylinder" rgba="1 1 1 1"/>
|
|
|
<geom size="0.011 0.0325" pos="0.02 0 -0.148" quat="0.999688 0 0.0249974 0" type="cylinder"/>
|
|
|
<geom size="0.0155 0.015" pos="0.00801333 0 -0.18745" quat="0.965093 0 0.261909 0" type="cylinder"/>
|
|
|
|
|
|
<body name="RR_foot" pos="0 0 -0.213">
|
|
|
<geom size="0.022" pos="0 0 0" rgba="0 0 0 1" friction="0.8 0.02 0.01" type="sphere"/>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
</body>
|
|
|
</worldbody>
|
|
|
|
|
|
<actuator>
|
|
|
<motor name="FR_hip" gear="23.7" joint="FR_hip_joint"/>
|
|
|
<motor name="FR_thigh" gear="23.7" joint="FR_thigh_joint"/>
|
|
|
<motor name="FR_calf" gear="35.5" joint="FR_calf_joint"/>
|
|
|
|
|
|
<motor name="FL_hip" gear="23.7" joint="FL_hip_joint"/>
|
|
|
<motor name="FL_thigh" gear="23.7" joint="FL_thigh_joint"/>
|
|
|
<motor name="FL_calf" gear="35.5" joint="FL_calf_joint"/>
|
|
|
|
|
|
<motor name="RR_hip" gear="23.7" joint="RR_hip_joint"/>
|
|
|
<motor name="RR_thigh" gear="23.7" joint="RR_thigh_joint"/>
|
|
|
<motor name="RR_calf" gear="35.5" joint="RR_calf_joint"/>
|
|
|
|
|
|
<motor name="RL_hip" gear="23.7" joint="RL_hip_joint"/>
|
|
|
<motor name="RL_thigh" gear="23.7" joint="RL_thigh_joint"/>
|
|
|
<motor name="RL_calf" gear="35.5" joint="RL_calf_joint"/>
|
|
|
</actuator>
|
|
|
|
|
|
|
|
|
<statistic center="1.0 0.7 1.0" 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>
|
|
|
|