quadruped_ros2_control/descriptions/quadruped_gazebo/urdf/a1/const.xacro

106 lines
4.8 KiB
Plaintext
Raw Normal View History

2024-09-09 22:18:19 +08:00
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="a1_description">
<!-- Constants for robot dimensions -->
<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.04"/>
<xacro:property name="thigh_shoulder_y_offset" value="-0.008"/>
<xacro:property name="thigh_width" value="0.03"/>
<xacro:property name="thigh_height" value="0.034"/>
<xacro:property name="thigh_x_offset" value="-0.015"/>
<xacro:property name="calf_width" value="0.016"/>
<xacro:property name="calf_height" value="0.016"/>
<xacro:property name="calf_x_offset" value="0.0"/>
<xacro:property name="foot_radius" value="0.02"/>
<!-- kinematic value -->
<xacro:property name="thigh_offset" value="0.0838"/>
<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.1805"/>
<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_position_max" value="${46*pi/180.0}"/>
<xacro:property name="hip_position_min" value="${-46*pi/180.0}"/>
<xacro:property name="hip_velocity_max" value="21"/>
<xacro:property name="hip_torque_max" value="33.5"/>
<xacro:property name="thigh_position_max" value="${240*pi/180.0}"/>
<xacro:property name="thigh_position_min" value="${-60*pi/180.0}"/>
<xacro:property name="thigh_velocity_max" value="21"/>
<xacro:property name="thigh_torque_max" value="33.5"/>
<xacro:property name="calf_position_max" value="${-52.5*pi/180.0}"/>
<xacro:property name="calf_position_min" value="${-154.5*pi/180.0}"/>
<xacro:property name="calf_velocity_max" value="21"/>
<xacro:property name="calf_torque_max" value="33.5"/>
<!-- dynamics inertial value -->
<!-- trunk -->
<xacro:property name="trunk_mass" value="6.0"/>
<xacro:property name="trunk_com_x" value="0.0000"/>
<xacro:property name="trunk_com_y" value="0.0041"/>
<xacro:property name="trunk_com_z" value="-0.0005"/>
<xacro:property name="trunk_ixx" value="0.0158533"/>
<xacro:property name="trunk_ixy" value="-0.0000366"/>
<xacro:property name="trunk_ixz" value="-0.0000611"/>
<xacro:property name="trunk_iyy" value="0.0377999"/>
<xacro:property name="trunk_iyz" value="-0.0000275"/>
<xacro:property name="trunk_izz" value="0.0456542"/>
<!-- hip (left front) -->
<xacro:property name="hip_mass" value="0.595"/>
<xacro:property name="hip_com_x" value="-0.003875"/>
<xacro:property name="hip_com_y" value="0.001622"/>
<xacro:property name="hip_com_z" value="0.000042"/>
<xacro:property name="hip_ixx" value="0.000402747"/>
<xacro:property name="hip_ixy" value="-0.000008709"/>
<xacro:property name="hip_ixz" value="-0.000000297"/>
<xacro:property name="hip_iyy" value="0.000691123"/>
<xacro:property name="hip_iyz" value="-0.000000545"/>
<xacro:property name="hip_izz" value="0.000487919"/>
<!-- thigh -->
<xacro:property name="thigh_mass" value="0.888"/>
<xacro:property name="thigh_com_x" value="-0.003574"/>
<xacro:property name="thigh_com_y" value="-0.019529"/>
<xacro:property name="thigh_com_z" value="-0.030323"/>
<xacro:property name="thigh_ixx" value="0.005251806"/>
<xacro:property name="thigh_ixy" value="-0.000002168"/>
<xacro:property name="thigh_ixz" value="0.000346889"/>
<xacro:property name="thigh_iyy" value="0.005000475"/>
<xacro:property name="thigh_iyz" value="-0.000028174"/>
<xacro:property name="thigh_izz" value="0.001110200"/>
<!-- calf -->
<xacro:property name="calf_mass" value="0.151"/>
<xacro:property name="calf_com_x" value="0.007105"/>
<xacro:property name="calf_com_y" value="-0.000239"/>
<xacro:property name="calf_com_z" value="-0.096933"/>
<xacro:property name="calf_ixx" value="0.002344758"/>
<xacro:property name="calf_ixy" value="0.0"/>
<xacro:property name="calf_ixz" value="-0.000141275"/>
<xacro:property name="calf_iyy" value="0.002360755"/>
<xacro:property name="calf_iyz" value="0.0"/>
<xacro:property name="calf_izz" value="0.000031158"/>
<!-- foot -->
<xacro:property name="foot_mass" value="0.06"/>
</robot>