121 lines
11 KiB
XML
121 lines
11 KiB
XML
<mujoco model="b1_description">
|
|
<compiler angle="radian" meshdir="../meshes/"/>
|
|
<asset>
|
|
<mesh name="trunk" file="trunk.stl"/>
|
|
<mesh name="hip" file="hip.stl"/>
|
|
<mesh name="thigh_mirror" file="thigh_mirror.stl"/>
|
|
<mesh name="calf" file="calf.stl"/>
|
|
<mesh name="thigh" file="thigh.stl"/>
|
|
</asset>
|
|
<worldbody>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="trunk"/>
|
|
<geom size="0.3235 0.15 0.075" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.0005 0.0005 0.0005" type="box" contype="0" conaffinity="0" group="1" density="0" rgba="0.8 0 0 1"/>
|
|
<geom size="0.0005 0.0005 0.0005" type="box" rgba="0.8 0 0 1"/>
|
|
<geom size="0.05 0.01" pos="0.1955 -0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0.1955 -0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0.1955 0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0.1955 0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="-0.1955 -0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="-0.1955 -0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="-0.1955 0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="-0.1955 0.072 0" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="FR_hip" pos="0.3455 -0.072 0">
|
|
<inertial pos="-0.018016 -0.00971213 9.67456e-05" quat="0.514022 0.512801 0.485949 0.486488" mass="2.366" diaginertia="0.00980696 0.00664332 0.0045362"/>
|
|
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.75 0.75"/>
|
|
<geom quat="0 1 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="hip"/>
|
|
<geom size="0.09 0.02" pos="0 -0.12675 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="FR_thigh" pos="0 -0.12675 0">
|
|
<inertial pos="-0.000220117 0.0301731 -0.0507383" quat="0.736596 -0.0378368 0.076521 0.670924" mass="4.2" diaginertia="0.0487177 0.0459334 0.00814802"/>
|
|
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" range="-1 3.5"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="thigh_mirror"/>
|
|
<geom size="0.175 0.025 0.04" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="FR_calf" pos="0 0 -0.35">
|
|
<inertial pos="0.0049483 0 -0.210919" quat="0.707231 -0.00481122 -0.00483372 0.70695" mass="0.907" diaginertia="0.0162164 0.0160695 0.000406131"/>
|
|
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.6 -0.6"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="calf"/>
|
|
<geom size="0.175 0.02 0.025" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.03" pos="0 0 -0.35" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.04" pos="0 0 -0.35" rgba="0 0.8 0 1"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="FL_hip" pos="0.3455 0.072 0">
|
|
<inertial pos="-0.018016 0.00971213 9.67456e-05" quat="0.486488 0.485949 0.512801 0.514022" mass="2.366" diaginertia="0.00980696 0.00664332 0.0045362"/>
|
|
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.75 0.75"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="hip"/>
|
|
<geom size="0.09 0.02" pos="0 0.12675 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="FL_thigh" pos="0 0.12675 0">
|
|
<inertial pos="-0.000220117 -0.0301731 -0.0507383" quat="0.670924 0.076521 -0.0378368 0.736596" mass="4.2" diaginertia="0.0487177 0.0459334 0.00814802"/>
|
|
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" range="-1 3.5"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="thigh"/>
|
|
<geom size="0.175 0.025 0.04" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="FL_calf" pos="0 0 -0.35">
|
|
<inertial pos="0.0049483 0 -0.210919" quat="0.707231 -0.00481122 -0.00483372 0.70695" mass="0.907" diaginertia="0.0162164 0.0160695 0.000406131"/>
|
|
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.6 -0.6"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="calf"/>
|
|
<geom size="0.175 0.02 0.025" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.03" pos="0 0 -0.35" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.04" pos="0 0 -0.35" rgba="0 0.8 0 1"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="RR_hip" pos="-0.3455 -0.072 0">
|
|
<inertial pos="0.018016 -0.00971213 9.67456e-05" quat="0.485949 0.486488 0.514022 0.512801" mass="2.366" diaginertia="0.00980696 0.00664332 0.0045362"/>
|
|
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.75 0.75"/>
|
|
<geom quat="0 0 0 -1" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="hip"/>
|
|
<geom size="0.09 0.02" pos="0 -0.12675 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="RR_thigh" pos="0 -0.12675 0">
|
|
<inertial pos="-0.000220117 0.0301731 -0.0507383" quat="0.736596 -0.0378368 0.076521 0.670924" mass="4.2" diaginertia="0.0487177 0.0459334 0.00814802"/>
|
|
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" range="-1 3.5"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="thigh_mirror"/>
|
|
<geom size="0.175 0.025 0.04" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="RR_calf" pos="0 0 -0.35">
|
|
<inertial pos="0.0049483 0 -0.210919" quat="0.707231 -0.00481122 -0.00483372 0.70695" mass="0.907" diaginertia="0.0162164 0.0160695 0.000406131"/>
|
|
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.6 -0.6"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="calf"/>
|
|
<geom size="0.175 0.02 0.025" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.03" pos="0 0 -0.35" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.04" pos="0 0 -0.35" rgba="0 0.8 0 1"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="RL_hip" pos="-0.3455 0.072 0">
|
|
<inertial pos="0.018016 0.00971213 9.67456e-05" quat="0.512801 0.514022 0.486488 0.485949" mass="2.366" diaginertia="0.00980696 0.00664332 0.0045362"/>
|
|
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" range="-0.75 0.75"/>
|
|
<geom quat="0 0 1 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="hip"/>
|
|
<geom size="0.09 0.02" pos="0 0.12675 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 0.00935 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="RL_thigh" pos="0 0.12675 0">
|
|
<inertial pos="-0.000220117 -0.0301731 -0.0507383" quat="0.670924 0.076521 -0.0378368 0.736596" mass="4.2" diaginertia="0.0487177 0.0459334 0.00814802"/>
|
|
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" range="-1 3.5"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="thigh"/>
|
|
<geom size="0.175 0.025 0.04" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.05 0.01" pos="0 -0.0519 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0 0.8 0 1"/>
|
|
<body name="RL_calf" pos="0 0 -0.35">
|
|
<inertial pos="0.0049483 0 -0.210919" quat="0.707231 -0.00481122 -0.00483372 0.70695" mass="0.907" diaginertia="0.0162164 0.0160695 0.000406131"/>
|
|
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" range="-2.6 -0.6"/>
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="1 0.423529 0.0392157 1" mesh="calf"/>
|
|
<geom size="0.175 0.02 0.025" pos="0 0 -0.175" quat="0.707107 0 0.707107 0" type="box" rgba="1 0.423529 0.0392157 1"/>
|
|
<geom size="0.03" pos="0 0 -0.35" contype="0" conaffinity="0" group="1" density="0" rgba="0 0.8 0 1"/>
|
|
<geom size="0.04" pos="0 0 -0.35" rgba="0 0.8 0 1"/>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</worldbody>
|
|
</mujoco>
|