unitree_mujoco/data/a1/urdf/a1.xml

140 lines
11 KiB
XML
Raw Normal View History

2021-11-01 16:51:26 +08:00
<mujoco model="a1_description">
<compiler angle="radian" meshdir="../meshes/" />
<option gravity="0 0 -9.8" />
<size njmax="500" nconmax="100" />
<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>
<light diffuse=".5 .5 .5" pos="0 0 3" dir="0 0 -1"/>
<geom type="plane" pos="0 0 -0.45" size="10 10 0.1" rgba=".9 0 0 1"/>
<body name="trunk" pos="0 0 0">
<inertial pos="0.0127283 0.00218554 0.000514891" quat="0.00186575 0.711506 0.000389649 0.702677" mass="4.714" diaginertia="0.0648213 0.0565803 0.0169323" />
<joint name="floating_base" type="free" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="trunk" />
<geom size="0.1335 0.097 0.057" type="box" rgba="0.913725 0.913725 0.847059 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.183 -0.047 0">
<inertial pos="-0.003311 -0.000635 3.1e-05" quat="0.507528 0.506268 0.491507 0.494499" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="FR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom quat="0 1 0 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 -0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="FR_thigh" pos="0 -0.08505 0">
<inertial pos="-0.003237 0.022327 -0.027326" quat="0.999125 -0.00256393 -0.0409531 -0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="FR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh_mirror" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="FR_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="FR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="FL_hip" pos="0.183 0.047 0">
<inertial pos="-0.003311 0.000635 3.1e-05" quat="0.494499 0.491507 0.506268 0.507528" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="FL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="FL_thigh" pos="0 0.08505 0">
<inertial pos="-0.003237 -0.022327 -0.027326" quat="0.999125 0.00256393 -0.0409531 0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="FL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="FL_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="FL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="RR_hip" pos="-0.183 -0.047 0">
<inertial pos="0.003311 -0.000635 3.1e-05" quat="0.491507 0.494499 0.507528 0.506268" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="RR_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom quat="0 0 0 -1" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 -0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="RR_thigh" pos="0 -0.08505 0">
<inertial pos="-0.003237 0.022327 -0.027326" quat="0.999125 -0.00256393 -0.0409531 -0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="RR_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh_mirror" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="RR_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="RR_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
<body name="RL_hip" pos="-0.183 0.047 0">
<inertial pos="0.003311 0.000635 3.1e-05" quat="0.506268 0.507528 0.494499 0.491507" mass="0.696" diaginertia="0.000807752 0.00055293 0.000468983" />
<joint name="RL_hip_joint" pos="0 0 0" axis="1 0 0" limited="true" range="-0.802851 0.802851" />
<geom quat="0 0 1 0" type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="hip" />
<geom size="0.04 0.04" pos="0 0.055 0" quat="0.707107 0.707107 0 0" type="cylinder" rgba="0.913725 0.913725 0.847059 0" />
<body name="RL_thigh" pos="0 0.08505 0">
<inertial pos="-0.003237 -0.022327 -0.027326" quat="0.999125 0.00256393 -0.0409531 0.00806091" mass="1.013" diaginertia="0.00555739 0.00513936 0.00133944" />
<joint name="RL_thigh_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-1.0472 4.18879" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0.913725 0.913725 0.847059 1" mesh="thigh" />
<geom size="0.1 0.01225 0.017" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0.913725 0.913725 0.847059 0" />
<body name="RL_calf" pos="0 0 -0.2">
<inertial pos="0.00472659 0 -0.131975" quat="0.706886 0.017653 0.017653 0.706886" mass="0.226" diaginertia="0.00340344 0.00339393 3.54834e-05" />
<joint name="RL_calf_joint" pos="0 0 0" axis="0 1 0" limited="true" range="-2.69653 -0.916298" />
<geom type="mesh" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" mesh="calf" />
<geom size="0.1 0.008 0.008" pos="0 0 -0.1" quat="0.707107 0 0.707107 0" type="box" rgba="0 0 0 0" />
<geom size="0.01" pos="0 0 -0.2" contype="0" conaffinity="0" group="1" rgba="0 0 0 1" />
<geom size="0.02" pos="0 0 -0.2" rgba="0 0 0 1" />
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<!--
<position joint="FR_hip_joint" kp="1000"/>
<position joint="FR_thigh_joint" kp="1000"/>
<position joint="FR_calf_joint" kp="1000"/>
<position joint="FL_hip_joint" kp="1000"/>
<position joint="FL_thigh_joint" kp="1000"/>
<position joint="FL_calf_joint" kp="1000"/>
<position joint="RR_hip_joint" kp="1000"/>
<position joint="RR_thigh_joint" kp="1000"/>
<position joint="RR_calf_joint" kp="1000"/>
<position joint="RL_hip_joint" kp="1000"/>
<position joint="RL_thigh_joint" kp="1000"/>
<position joint="RL_calf_joint" kp="1000"/> -->
<motor name="FR_hip" gear="9.1" joint="FR_hip_joint" forcerange="-33.5 33.5" />
<motor name="FR_thigh" gear="9.1" joint="FR_thigh_joint" forcerange="-33.5 33.5" />
<motor name="FR_calf" gear="9.1" joint="FR_calf_joint" forcerange="-33.5 33.5" />
<motor name="FL_hip" gear="9.1" joint="FL_hip_joint" forcerange="-33.5 33.5" />
<motor name="FL_thigh" gear="9.1" joint="FL_thigh_joint" forcerange="-33.5 33.5" />
<motor name="FL_calf" gear="9.1" joint="FL_calf_joint" forcerange="-33.5 33.5" />
<motor name="RR_hip" gear="9.1" joint="RR_hip_joint" forcerange="-33.5 33.5" />
<motor name="RR_thigh" gear="9.1" joint="RR_thigh_joint" forcerange="-33.5 33.5" />
<motor name="RR_calf" gear="9.1" joint="RR_calf_joint" forcerange="-33.5 33.5" />
<motor name="RL_hip" gear="9.1" joint="RL_hip_joint" forcerange="-33.5 33.5" />
<motor name="RL_thigh" gear="9.1" joint="RL_thigh_joint" forcerange="-33.5 33.5" />
<motor name="RL_calf" gear="9.1" joint="RL_calf_joint" forcerange="-33.5 33.5" />
</actuator>
</mujoco>