unitree_mujoco/data/aliengo/urdf/aliengo.xml

170 lines
12 KiB
XML
Raw Normal View History

2021-11-02 12:21:40 +08:00
<mujoco model="aliengo_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.5">
<inertial pos="0.00846406 0.00404455 -0.000762916" quat="-3.12625e-05 0.708321 0.00247254 0.705886" mass="9.042" diaginertia="0.174706 0.161175 0.033357" />
<joint name="floating_base" type="free" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="trunk" />
<geom size="0.3235 0.075 0.056" type="box" rgba="0.2 0.2 0.2 0" />
<geom size="0.0005 0.0005 0.0005" type="box" contype="0" conaffinity="0" group="1" rgba="0.8 0 0 0" />
<geom size="0.0005 0.0005 0.0005" type="box" rgba="0.8 0 0 0" />
<body name="FR_hip" pos="0.2399 -0.051 0">
<inertial pos="-0.022191 -0.015144 -1.5e-05" quat="0.0135493 0.706835 -0.0117635 0.707151" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
<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.046 0.0209" pos="0 -0.083 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.083 0">
<inertial pos="-0.005607 0.003877 -0.048199" quat="0.694544 -0.0335669 -0.031246 0.717987" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" />
<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.0187 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.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="FL_hip" pos="0.2399 0.051 0">
<inertial pos="-0.022191 0.015144 -1.5e-05" quat="-0.0135493 0.706835 0.0117635 0.707151" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="hip" />
<geom size="0.046 0.0209" pos="0 0.083 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.083 0">
<inertial pos="-0.005607 -0.003877 -0.048199" quat="0.717987 -0.031246 -0.0335669 0.694544" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
<geom size="0.125 0.0187 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.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="RR_hip" pos="-0.2399 -0.051 0">
<inertial pos="0.022191 -0.015144 -1.5e-05" quat="-0.0117635 0.707151 0.0135493 0.706835" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
<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.046 0.0209" pos="0 -0.083 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.083 0">
<inertial pos="-0.005607 0.003877 -0.048199" quat="0.694544 -0.0335669 -0.031246 0.717987" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" />
<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.0187 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.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="RL_hip" pos="-0.2399 0.051 0">
<inertial pos="0.022191 0.015144 -1.5e-05" quat="0.0117635 0.707151 -0.0135493 0.706835" mass="1.993" diaginertia="0.00558695 0.00491009 0.00290132" />
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-1.22173 1.22173" />
<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.046 0.0209" pos="0 0.083 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.083 0">
<inertial pos="-0.005607 -0.003877 -0.048199" quat="0.717987 -0.031246 -0.0335669 0.694544" mass="0.639" diaginertia="0.0058474 0.00571186 0.000324584" />
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.2 0.2 0.2 1" mesh="thigh" />
<geom size="0.125 0.0187 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.00215606 4.88427e-05 -0.166671" quat="0.707462 0.00517582 0.00535172 0.706712" mass="0.267" diaginertia="0.00690975 0.00689712 5.4885e-05" />
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.77507 -0.645772" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.125 0.0104 0.008" pos="0 0 -0.125" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.0165" pos="0 0 -0.25" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.0265" pos="0 0 -0.25" rgba="0 0 0 1" />
</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>