unitree_ros/robots/a1_description/xacro/const.xacro

105 lines
4.7 KiB
Plaintext
Raw Normal View History

2020-07-15 11:21:03 +08:00
<?xml version="1.0"?>
<robot name="a1_description" xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="stick_mass" value="0.00001"/>
<!-- simplified collision value -->
<xacro:property name="trunk_width" value="0.194"/>
<xacro:property name="trunk_length" value="0.267"/>
<xacro:property name="trunk_height" value="0.114"/>
<xacro:property name="hip_radius" value="0.046"/>
<xacro:property name="hip_length" value="0.04"/>
<xacro:property name="thigh_shoulder_radius" value="0.041"/>
<xacro:property name="thigh_shoulder_length" value="0.032"/>
<xacro:property name="thigh_width" value="0.0245"/>
<xacro:property name="thigh_height" value="0.034"/>
<xacro:property name="calf_width" value="0.016"/>
<xacro:property name="calf_height" value="0.016"/>
<xacro:property name="foot_radius" value="0.02"/>
<xacro:property name="stick_radius" value="0.01"/>
<xacro:property name="stick_length" value="0.2"/>
<!-- kinematic value -->
<xacro:property name="thigh_offset" value="0.08505"/>
<xacro:property name="thigh_length" value="0.2"/>
<xacro:property name="calf_length" value="0.2"/>
<!-- leg offset from trunk center value -->
<xacro:property name="leg_offset_x" value="0.183"/>
<xacro:property name="leg_offset_y" value="0.047"/>
<xacro:property name="trunk_offset_z" value="0.01675"/>
<xacro:property name="hip_offset" value="0.065"/>
<!-- joint limits -->
<xacro:property name="damping" value="0"/>
<xacro:property name="friction" value="0"/>
<xacro:property name="hip_max" value="46"/>
<xacro:property name="hip_min" value="-46"/>
<xacro:property name="hip_velocity_max" value="52.4"/>
<xacro:property name="hip_torque_max" value="20"/>
<xacro:property name="thigh_max" value="240"/>
<xacro:property name="thigh_min" value="-60"/>
<xacro:property name="thigh_velocity_max" value="28.6"/>
<xacro:property name="thigh_torque_max" value="55"/>
<xacro:property name="calf_max" value="-52.5"/>
<xacro:property name="calf_min" value="-154.5"/>
<xacro:property name="calf_velocity_max" value="28.6"/>
<xacro:property name="calf_torque_max" value="55"/>
<!-- dynamics inertial value -->
<!-- trunk -->
<xacro:property name="trunk_mass" value="4.713"/>
<xacro:property name="trunk_com_x" value="0.012731"/>
<xacro:property name="trunk_com_y" value="0.002186"/>
<xacro:property name="trunk_com_z" value="0.000515"/>
<xacro:property name="trunk_ixx" value="0.016839930"/>
<xacro:property name="trunk_ixy" value="0.000083902"/>
<xacro:property name="trunk_ixz" value="0.000597679"/>
<xacro:property name="trunk_iyy" value="0.056579028"/>
<xacro:property name="trunk_iyz" value="0.000025134"/>
<xacro:property name="trunk_izz" value="0.064713601"/>
<!-- hip (left front) -->
<xacro:property name="hip_mass" value="0.696"/>
<xacro:property name="hip_com_x" value="-0.003311"/>
<xacro:property name="hip_com_y" value="0.000635"/>
<xacro:property name="hip_com_z" value="0.000031"/>
<xacro:property name="hip_ixx" value="0.000469246"/>
<xacro:property name="hip_ixy" value="-0.000009409"/>
<xacro:property name="hip_ixz" value="-0.000000342"/>
<xacro:property name="hip_iyy" value="0.000807490"/>
<xacro:property name="hip_iyz" value="-0.000000466"/>
<xacro:property name="hip_izz" value="0.000552929"/>
<!-- thigh -->
<xacro:property name="thigh_mass" value="1.013"/>
<xacro:property name="thigh_com_x" value="-0.003237"/>
<xacro:property name="thigh_com_y" value="-0.022327"/>
<xacro:property name="thigh_com_z" value="-0.027326"/>
<xacro:property name="thigh_ixx" value="0.005529065"/>
<xacro:property name="thigh_ixy" value="0.000004825"/>
<xacro:property name="thigh_ixz" value="0.000343869"/>
<xacro:property name="thigh_iyy" value="0.005139339"/>
<xacro:property name="thigh_iyz" value="0.000022448"/>
<xacro:property name="thigh_izz" value="0.001367788"/>
<!-- calf -->
<xacro:property name="calf_mass" value="0.166"/>
<xacro:property name="calf_com_x" value="0.006435"/>
<xacro:property name="calf_com_y" value="0.0"/>
<xacro:property name="calf_com_z" value="-0.107388"/>
<xacro:property name="calf_ixx" value="0.002997972"/>
<xacro:property name="calf_ixy" value="0.0"/>
<xacro:property name="calf_ixz" value="-0.000141163"/>
<xacro:property name="calf_iyy" value="0.003014022"/>
<xacro:property name="calf_iyz" value="0.0"/>
<xacro:property name="calf_izz" value="0.000032426"/>
<!-- foot -->
<xacro:property name="foot_mass" value="0.06"/>
</robot>