unitree_ros/robots/laikago_description/xacro/const.xacro

105 lines
4.7 KiB
XML

<?xml version="1.0"?>
<robot 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.172"/>
<xacro:property name="trunk_length" value="0.5616"/>
<xacro:property name="trunk_height" value="0.1875"/>
<xacro:property name="hip_radius" value="0.041"/>
<xacro:property name="hip_length" value="0.08"/>
<xacro:property name="thigh_shoulder_radius" value="0.044"/>
<xacro:property name="thigh_shoulder_length" value="0.08"/>
<xacro:property name="thigh_width" value="0.034"/>
<xacro:property name="thigh_height" value="0.043"/>
<xacro:property name="calf_width" value="0.016"/>
<xacro:property name="calf_height" value="0.016"/>
<xacro:property name="foot_radius" value="0.0265"/>
<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.037"/>
<xacro:property name="thigh_length" value="0.25"/>
<xacro:property name="calf_length" value="0.25"/>
<!-- leg offset from trunk center value -->
<xacro:property name="leg_offset_x" value="0.21935"/>
<xacro:property name="leg_offset_y" value="0.0875"/>
<xacro:property name="trunk_offset_z" value="0.01675"/>
<xacro:property name="hip_offset" value="0.019"/>
<!-- joint limits -->
<xacro:property name="damping" value="0"/>
<xacro:property name="friction" value="0"/>
<xacro:property name="hip_max" value="60"/>
<xacro:property name="hip_min" value="-50"/>
<xacro:property name="hip_velocity_max" value="27"/>
<xacro:property name="hip_torque_max" value="18.954"/>
<xacro:property name="thigh_max" value="225"/>
<xacro:property name="thigh_min" value="-30"/>
<xacro:property name="thigh_velocity_max" value="12.794"/>
<xacro:property name="thigh_torque_max" value="40"/>
<xacro:property name="calf_max" value="-35"/>
<xacro:property name="calf_min" value="-159"/>
<xacro:property name="calf_velocity_max" value="12.794"/>
<xacro:property name="calf_torque_max" value="40"/>
<!-- dynamics inertial value -->
<!-- trunk -->
<xacro:property name="trunk_mass" value="13.733"/>
<xacro:property name="trunk_com_x" value="0.002284"/>
<xacro:property name="trunk_com_y" value="-0.000041"/>
<xacro:property name="trunk_com_z" value="0.025165"/>
<xacro:property name="trunk_ixx" value="0.073348887"/>
<xacro:property name="trunk_ixy" value="0.00030338"/>
<xacro:property name="trunk_ixz" value="0.001918218"/>
<xacro:property name="trunk_iyy" value="0.250684593"/>
<xacro:property name="trunk_iyz" value="-0.000075402"/>
<xacro:property name="trunk_izz" value="0.254469458"/>
<!-- hip (left front) -->
<xacro:property name="hip_mass" value="1.096"/>
<xacro:property name="hip_com_x" value="-0.001568"/>
<xacro:property name="hip_com_y" value="-0.008134"/>
<xacro:property name="hip_com_z" value="0.000864"/>
<xacro:property name="hip_ixx" value="0.000822113"/>
<xacro:property name="hip_ixy" value="-0.000004982"/>
<xacro:property name="hip_ixz" value="-0.00003672"/>
<xacro:property name="hip_iyy" value="0.000983196"/>
<xacro:property name="hip_iyz" value="0.000002811"/>
<xacro:property name="hip_izz" value="0.000864753"/>
<!-- thigh -->
<xacro:property name="thigh_mass" value="1.528"/>
<xacro:property name="thigh_com_x" value="-0.000482"/>
<xacro:property name="thigh_com_y" value="0.02001"/>
<xacro:property name="thigh_com_z" value="-0.031996"/>
<xacro:property name="thigh_ixx" value="0.00991611"/>
<xacro:property name="thigh_ixy" value="0.000010388"/>
<xacro:property name="thigh_ixz" value="0.000250428"/>
<xacro:property name="thigh_iyy" value="0.009280083"/>
<xacro:property name="thigh_iyz" value="-0.00008511"/>
<xacro:property name="thigh_izz" value="0.00178256"/>
<!-- calf -->
<xacro:property name="calf_mass" value="0.241"/>
<xacro:property name="calf_com_x" value="-0.002196"/>
<xacro:property name="calf_com_y" value="-0.000381"/>
<xacro:property name="calf_com_z" value="-0.12338"/>
<xacro:property name="calf_ixx" value="0.006181961"/>
<xacro:property name="calf_ixy" value="0.000000237"/>
<xacro:property name="calf_ixz" value="-0.000002985"/>
<xacro:property name="calf_iyy" value="0.006196546"/>
<xacro:property name="calf_iyz" value="0.000005138"/>
<xacro:property name="calf_izz" value="0.000034774"/>
<!-- foot -->
<xacro:property name="foot_mass" value="0.06"/>
</robot>