160 lines
12 KiB
XML
160 lines
12 KiB
XML
<mujoco model="laikago_description">
|
|
<compiler angle="radian" meshdir="../meshes/" />
|
|
<size njmax="500" nconmax="100" />
|
|
<option gravity='0 0 -9.806' iterations='50' solver='Newton' timestep='0.002'/>
|
|
|
|
<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"/>
|
|
|
|
<light castshadow="false" diffuse="1 1 1"/>
|
|
<motor ctrlrange="-33.5 33.5" ctrllimited="true"/>
|
|
<camera fovy="60"/>
|
|
<joint damping="0.01" armature="0.01"/>
|
|
|
|
</default>
|
|
|
|
<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>
|
|
|
|
<asset>
|
|
<texture type="skybox" builtin="gradient" rgb1="1.0 1.0 1.0" rgb2="1.0 1.0 1.0" width="512" height="512"/>
|
|
<texture name="plane" type="2d" builtin="flat" rgb1="1 1 1" rgb2="1 1 1" width="512" height="512" mark="cross" markrgb="0 0 0"/>
|
|
<material name="plane" reflectance="0.0" texture="plane" texrepeat="3 3" texuniform="true"/>
|
|
</asset>
|
|
<worldbody>
|
|
<light directional="true" diffuse=".8 .8 .8" pos="0 0 10" dir="0 0 -10"/>
|
|
<camera name="track" mode="trackcom" pos="0 -1.3 1.6" xyaxes="1 0 0 0 0.707 0.707"/>
|
|
<geom name='floor' type='plane' conaffinity='1' condim='3' contype='1' rgba="0.5 0.9 0.9 0.1" material='plane' pos='0 0 0' size='0 0 1'/>
|
|
|
|
<body name="trunk" pos="0 0 0.55">
|
|
<inertial pos="0.002284 -4.1e-05 0.025165" quat="-0.00605949 0.710803 -0.00734309 0.703327" mass="13.733" diaginertia="0.254491 0.250684 0.0733281" />
|
|
<joint type="free" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="trunk" />
|
|
<geom size="0.2808 0.086 0.09375" pos="0 0 0.01675" type="box" rgba="0.2 0.2 0.2 0" />
|
|
<body name="FR_hip" pos="0.21935 -0.0875 0">
|
|
<inertial pos="-0.001568 0.008134 0.000864" quat="0.629953 0.350191 0.35823 0.593462" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
|
|
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.0472 0.872665" />
|
|
<geom quat="0 1 0 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
|
<geom size="0.041 0.04" pos="0 0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
|
<body name="FR_thigh" pos="0 -0.037 0">
|
|
<inertial pos="-0.000482 -0.02001 -0.031996" quat="0.999848 0.00577968 -0.0153453 -0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
|
|
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh_mirror" />
|
|
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
|
<body name="FR_calf" pos="0 0 -0.25">
|
|
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
|
|
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
|
|
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="FL_hip" pos="0.21935 0.0875 0">
|
|
<inertial pos="-0.001568 -0.008134 0.000864" quat="0.593462 0.35823 0.350191 0.629953" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
|
|
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.872665 1.0472" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
|
<geom size="0.041 0.04" pos="0 -0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
|
<body name="FL_thigh" pos="0 0.037 0">
|
|
<inertial pos="-0.000482 0.02001 -0.031996" quat="0.999848 -0.00577968 -0.0153453 0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
|
|
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
|
|
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
|
<body name="FL_calf" pos="0 0 -0.25">
|
|
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
|
|
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
|
|
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="RR_hip" pos="-0.21935 -0.0875 0">
|
|
<inertial pos="0.001568 0.008134 0.000864" quat="0.35823 0.593462 0.629953 0.350191" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
|
|
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.0472 0.872665" />
|
|
<geom quat="0 0 0 -1" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
|
<geom size="0.041 0.04" pos="0 0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
|
<body name="RR_thigh" pos="0 -0.037 0">
|
|
<inertial pos="-0.000482 -0.02001 -0.031996" quat="0.999848 0.00577968 -0.0153453 -0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
|
|
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh_mirror" />
|
|
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
|
<body name="RR_calf" pos="0 0 -0.25">
|
|
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
|
|
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
|
|
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
|
</body>
|
|
</body>
|
|
</body>
|
|
<body name="RL_hip" pos="-0.21935 0.0875 0">
|
|
<inertial pos="0.001568 -0.008134 0.000864" quat="0.350191 0.629953 0.593462 0.35823" mass="1.096" diaginertia="0.000983491 0.000885646 0.000800926" />
|
|
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.872665 1.0472" />
|
|
<geom quat="0 0 1 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
|
|
<geom size="0.041 0.04" pos="0 -0.021 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.2 0.2 0.2 0" />
|
|
<body name="RL_thigh" pos="0 0.037 0">
|
|
<inertial pos="-0.000482 0.02001 -0.031996" quat="0.999848 -0.00577968 -0.0153453 0.00595156" mass="1.528" diaginertia="0.00992391 0.00928096 0.00177389" />
|
|
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-0.523599 3.92699" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
|
|
<geom size="0.125 0.017 0.0215" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.2 0.2 0.2 0" />
|
|
<body name="RL_calf" pos="0 0 -0.25">
|
|
<inertial pos="-0.002196 -0.000381 -0.12338" quat="0.712765 0.000467477 -0.000119366 0.701402" mass="0.241" diaginertia="0.00619655 0.00618196 3.47683e-05" />
|
|
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.610865" />
|
|
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="calf" />
|
|
<geom size="0.125 0.008 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</body>
|
|
</worldbody>
|
|
<actuator>
|
|
|
|
<motor name="FR_hip" gear="1" joint="FR_hip_joint"/>
|
|
<motor name="FR_thigh" gear="1" joint="FR_thigh_joint"/>
|
|
<motor name="FR_calf" gear="1" joint="FR_calf_joint"/>
|
|
<motor name="FL_hip" gear="1" joint="FL_hip_joint"/>
|
|
<motor name="FL_thigh" gear="1" joint="FL_thigh_joint"/>
|
|
<motor name="FL_calf" gear="1" joint="FL_calf_joint"/>
|
|
<motor name="RR_hip" gear="1" joint="RR_hip_joint"/>
|
|
<motor name="RR_thigh" gear="1" joint="RR_thigh_joint"/>
|
|
<motor name="RR_calf" gear="1" joint="RR_calf_joint" />
|
|
<motor name="RL_hip" gear="1" joint="RL_hip_joint"/>
|
|
<motor name="RL_thigh" gear="1" joint="RL_thigh_joint"/>
|
|
<motor name="RL_calf" gear="1" joint="RL_calf_joint"/>
|
|
</actuator>
|
|
|
|
<sensor>
|
|
|
|
<jointpos name="FR_hip_pos" joint="FR_hip_joint"/>
|
|
<jointpos name="FR_thigh_pos" joint="FR_thigh_joint"/>
|
|
<jointpos name="FR_calf_pos" joint="FR_calf_joint"/>
|
|
<jointpos name="FL_hip_pos" joint="FL_hip_joint"/>
|
|
<jointpos name="FL_thigh_pos" joint="FL_thigh_joint"/>
|
|
<jointpos name="FL_calf_pos" joint="FL_calf_joint"/>
|
|
<jointpos name="RR_hip_pos" joint="RR_hip_joint"/>
|
|
<jointpos name="RR_thigh_pos" joint="RR_thigh_joint"/>
|
|
<jointpos name="RR_calf_pos" joint="RR_calf_joint" />
|
|
<jointpos name="RL_hip_pos" joint="RL_hip_joint"/>
|
|
<jointpos name="RL_thigh_pos" joint="RL_thigh_joint"/>
|
|
<jointpos name="RL_calf_pos" joint="RL_calf_joint"/>
|
|
|
|
<jointvel name="FR_hip_vel" joint="FR_hip_joint"/>
|
|
<jointvel name="FR_thigh_vel" joint="FR_thigh_joint"/>
|
|
<jointvel name="FR_calf_vel" joint="FR_calf_joint"/>
|
|
<jointvel name="FL_hip_vel" joint="FL_hip_joint"/>
|
|
<jointvel name="FL_thigh_vel" joint="FL_thigh_joint"/>
|
|
<jointvel name="FL_calf_vel" joint="FL_calf_joint"/>
|
|
<jointvel name="RR_hip_vel" joint="RR_hip_joint"/>
|
|
<jointvel name="RR_thigh_vel" joint="RR_thigh_joint"/>
|
|
<jointvel name="RR_calf_vel" joint="RR_calf_joint" />
|
|
<jointvel name="RL_hip_vel" joint="RL_hip_joint"/>
|
|
<jointvel name="RL_thigh_vel" joint="RL_thigh_joint"/>
|
|
<jointvel name="RL_calf_vel" joint="RL_calf_joint"/>
|
|
|
|
</sensor>
|
|
|
|
</mujoco>
|