Go2Py_SIM/locomotion/src/robots/b1_description/mujoco/b1.xml

231 lines
17 KiB
XML

<mujoco model="b1_description">
<compiler angle="radian" meshdir="../meshes/" autolimits="true"/>
<option cone="elliptic" impratio="100"/>
<default>
<default class="b1">
<geom friction="0.6" margin="0.001" condim="1"/>
<joint axis="0 1 0" damping="2" armature="0.01" frictionloss="0.2"/>
<motor ctrlrange="-230.7 230.7"/>
<default class="abduction">
<joint axis="1 0 0" range="-3.0472 3.0472"/>
</default>
<default class="hip">
<default class="front_hip">
<joint range="-3.5708 6.4907"/>
</default>
<default class="back_hip">
<joint range="-1.5236 8.5379"/>
</default>
</default>
<default class="knee">
<joint range="-4.7227 -1.83776"/>
<motor ctrlrange="-450.43 450.43"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="2"/>
</default>
<default class="collision">
<geom group="3"/>
<default class="foot">
<geom size="0.022" pos="-0.002 0 -0.213" priority="1" solimp="0.015 1 0.031" condim="6"
friction="0.8 0.02 0.01"/>
</default>
</default>
</default>
</default>
<asset>
<material name="metal" rgba=".9 .95 .95 1"/>
<material name="black" rgba="0 0 0 1"/>
<material name="white" rgba="1 1 1 1"/>
<material name="gray" rgba="0.671705 0.692426 0.774270 1"/>
<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>
<body name="base" pos="0 0 0.85" childclass="b1">
<inertial pos="0.00870935 0.0021737 0.00291991" quat="0.00194753 0.691276 0.00346027 0.72258" mass="25.797" diaginertia="0.820612 0.7877 0.187707"/>
<joint name="floating_base" type="free"/>
<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"/>
<site name="imu" pos="-0.02557 0 0.04232"/>
<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>
</body>
</worldbody>
<actuator>
<motor class="abduction" name="FL_hip" joint="FL_hip_joint"/>
<motor class="hip" name="FL_thigh" joint="FL_thigh_joint"/>
<motor class="knee" name="FL_calf" joint="FL_calf_joint"/>
<motor class="abduction" name="FR_hip" joint="FR_hip_joint"/>
<motor class="hip" name="FR_thigh" joint="FR_thigh_joint"/>
<motor class="knee" name="FR_calf" joint="FR_calf_joint"/>
<motor class="abduction" name="RL_hip" joint="RL_hip_joint"/>
<motor class="hip" name="RL_thigh" joint="RL_thigh_joint"/>
<motor class="knee" name="RL_calf" joint="RL_calf_joint"/>
<motor class="abduction" name="RR_hip" joint="RR_hip_joint"/>
<motor class="hip" name="RR_thigh" joint="RR_thigh_joint"/>
<motor class="knee" name="RR_calf" joint="RR_calf_joint"/>
</actuator>
<sensor>
<jointpos name="FL_hip_position_sensor" joint="FL_hip_joint" noise="0.001"/>
<jointpos name="FL_thigh_position_sensor" joint="FL_thigh_joint" noise="0.001"/>
<jointpos name="FL_calf_position_sensor" joint="FL_calf_joint" noise="0.001"/>
<jointpos name="FR_hip_position_sensor" joint="FR_hip_joint" noise="0.001"/>
<jointpos name="FR_thigh_position_sensor" joint="FR_thigh_joint" noise="0.001"/>
<jointpos name="FR_calf_position_sensor" joint="FR_calf_joint" noise="0.001"/>
<jointpos name="RL_hip_position_sensor" joint="RL_hip_joint" noise="0.001"/>
<jointpos name="RL_thigh_position_sensor" joint="RL_thigh_joint" noise="0.001"/>
<jointpos name="RL_calf_position_sensor" joint="RL_calf_joint" noise="0.001"/>
<jointpos name="RR_hip_position_sensor" joint="RR_hip_joint" noise="0.001"/>
<jointpos name="RR_thigh_position_sensor" joint="RR_thigh_joint" noise="0.001"/>
<jointpos name="RR_calf_position_sensor" joint="RR_calf_joint" noise="0.001"/>
<jointvel name="FL_hip_velocity_sensor" joint="FL_hip_joint" noise="0.001"/>
<jointvel name="FL_thigh_velocity_sensor" joint="FL_thigh_joint" noise="0.001"/>
<jointvel name="FL_calf_velocity_sensor" joint="FL_calf_joint" noise="0.001"/>
<jointvel name="FR_hip_velocity_sensor" joint="FR_hip_joint" noise="0.001"/>
<jointvel name="FR_thigh_velocity_sensor" joint="FR_thigh_joint" noise="0.001"/>
<jointvel name="FR_calf_velocity_sensor" joint="FR_calf_joint" noise="0.001"/>
<jointvel name="RL_hip_velocity_sensor" joint="RL_hip_joint" noise="0.001"/>
<jointvel name="RL_thigh_velocity_sensor" joint="RL_thigh_joint" noise="0.001"/>
<jointvel name="RL_calf_velocity_sensor" joint="RL_calf_joint" noise="0.001"/>
<jointvel name="RR_hip_velocity_sensor" joint="RR_hip_joint" noise="0.001"/>
<jointvel name="RR_thigh_velocity_sensor" joint="RR_thigh_joint" noise="0.001"/>
<jointvel name="RR_calf_velocity_sensor" joint="RR_calf_joint" noise="0.001"/>
<jointactuatorfrc name="FL_hip_force_sensor" joint="FL_hip_joint" noise="0.001"/>
<jointactuatorfrc name="FL_thigh_force_sensor" joint="FL_thigh_joint" noise="0.001"/>
<jointactuatorfrc name="FL_calf_force_sensor" joint="FL_calf_joint" noise="0.001"/>
<jointactuatorfrc name="FR_hip_force_sensor" joint="FR_hip_joint" noise="0.001"/>
<jointactuatorfrc name="FR_thigh_force_sensor" joint="FR_thigh_joint" noise="0.001"/>
<jointactuatorfrc name="FR_calf_force_sensor" joint="FR_calf_joint" noise="0.001"/>
<jointactuatorfrc name="RL_hip_force_sensor" joint="RL_hip_joint" noise="0.001"/>
<jointactuatorfrc name="RL_thigh_force_sensor" joint="RL_thigh_joint" noise="0.001"/>
<jointactuatorfrc name="RL_calf_force_sensor" joint="RL_calf_joint" noise="0.001"/>
<jointactuatorfrc name="RR_hip_force_sensor" joint="RR_hip_joint" noise="0.001"/>
<jointactuatorfrc name="RR_thigh_force_sensor" joint="RR_thigh_joint" noise="0.001"/>
<jointactuatorfrc name="RR_calf_force_sensor" joint="RR_calf_joint" noise="0.001"/>
<accelerometer name="linear_acceleration" site="imu" noise="0.001"/>
<gyro name="angular_velocity" site="imu" noise="0.001"/>
<framequat name="imu_orientation" objtype="site" objname="imu" noise="0.001"/>
</sensor>
<keyframe>
<key name="home" qpos="0 0 0.45 1 0 0 0 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8"
ctrl="0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8 0 0.9 -1.8"/>
</keyframe>
</mujoco>