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

142 lines
6.3 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">
<!-- Constants for robot dimensions -->
<xacro:property name="PI" value="3.1415926535897931"/>
<!-- simplified collision value -->
<xacro:property name="trunk_width" value="0.0935"/>
<xacro:property name="trunk_length" value="0.3762"/>
<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_shoulder_y_offset" value="-0.008"/>
<xacro:property name="thigh_width" value="0.0245"/>
<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.08"/>
<xacro:property name="thigh_length" value="0.213"/>
<xacro:property name="calf_length" value="0.213"/>
<!-- leg offset from trunk center value -->
<xacro:property name="leg_offset_x" value="0.1881"/>
<xacro:property name="leg_offset_y" value="0.04675"/>
<!-- <xacro:property name="trunk_offset_z" value="0.01675"/> -->
<xacro:property name="hip_offset" value="0.08"/>
<!-- offset of link and rotor locations (left front) -->
<xacro:property name="hip_offset_x" value="0.1881"/>
<xacro:property name="hip_offset_y" value="0.04675"/>
<xacro:property name="hip_offset_z" value="0.0"/>
<xacro:property name="hip_rotor_offset_x" value="0.11215"/>
<xacro:property name="hip_rotor_offset_y" value="0.04675"/>
<xacro:property name="hip_rotor_offset_z" value="0.0"/>
<xacro:property name="thigh_offset_x" value="0"/>
<xacro:property name="thigh_offset_y" value="0.08"/>
<xacro:property name="thigh_offset_z" value="0.0"/>
<xacro:property name="thigh_rotor_offset_x" value="0.0"/>
<xacro:property name="thigh_rotor_offset_y" value="-0.00015"/>
<xacro:property name="thigh_rotor_offset_z" value="0.0"/>
<xacro:property name="calf_offset_x" value="0.0"/>
<xacro:property name="calf_offset_y" value="0.0"/>
<xacro:property name="calf_offset_z" value="-0.213"/>
<xacro:property name="calf_rotor_offset_x" value="0.0"/>
<xacro:property name="calf_rotor_offset_y" value="-0.03235"/>
<xacro:property name="calf_rotor_offset_z" value="0.0"/>
<!-- joint limits -->
<xacro:property name="damping" value="0.01"/>
<xacro:property name="friction" value="0.2"/>
<xacro:property name="hip_position_max" value="0.863"/>
<xacro:property name="hip_position_min" value="-0.863"/>
<xacro:property name="hip_velocity_max" value="30.1"/>
<xacro:property name="hip_torque_max" value="23.7"/>
<xacro:property name="thigh_position_max" value="4.501"/>
<xacro:property name="thigh_position_min" value="-0.686"/>
<xacro:property name="thigh_velocity_max" value="30.1"/>
<xacro:property name="thigh_torque_max" value="23.7"/>
<xacro:property name="calf_position_max" value="-0.888"/>
<xacro:property name="calf_position_min" value="-2.818"/>
<xacro:property name="calf_velocity_max" value="20.06"/>
<xacro:property name="calf_torque_max" value="35.55"/>
<!-- dynamics inertial value total 12.84kg -->
<!-- trunk -->
<xacro:property name="trunk_mass" value="5.204"/>
<xacro:property name="trunk_com_x" value="0.0223"/>
<xacro:property name="trunk_com_y" value="0.002"/>
<xacro:property name="trunk_com_z" value="-0.0005"/>
<xacro:property name="trunk_ixx" value="0.0168128557"/>
<xacro:property name="trunk_ixy" value="-0.0002296769"/>
<xacro:property name="trunk_ixz" value="-0.0002945293"/>
<xacro:property name="trunk_iyy" value="0.063009565"/>
<xacro:property name="trunk_iyz" value="-0.0000418731"/>
<xacro:property name="trunk_izz" value="0.0716547275"/>
<!-- hip (left front) -->
<xacro:property name="hip_mass" value="0.591"/>
<xacro:property name="hip_com_x" value="-0.005657"/>
<xacro:property name="hip_com_y" value="-0.008752"/>
<xacro:property name="hip_com_z" value="-0.000102"/>
<xacro:property name="hip_ixx" value="0.000334008405"/>
<xacro:property name="hip_ixy" value="-0.000010826066"/>
<xacro:property name="hip_ixz" value="0.000001290732"/>
<xacro:property name="hip_iyy" value="0.000619101213"/>
<xacro:property name="hip_iyz" value="0.000001643194"/>
<xacro:property name="hip_izz" value="0.00040057614"/>
<!-- thigh -->
<xacro:property name="thigh_mass" value="0.92"/>
<xacro:property name="thigh_com_x" value="-0.003342"/>
<xacro:property name="thigh_com_y" value="-0.018054"/>
<xacro:property name="thigh_com_z" value="-0.033451"/>
<xacro:property name="thigh_ixx" value="0.004431760472"/>
<xacro:property name="thigh_ixy" value="0.000057496807"/>
<xacro:property name="thigh_ixz" value="-0.000218457134"/>
<xacro:property name="thigh_iyy" value="0.004485671726"/>
<xacro:property name="thigh_iyz" value="0.000572001265"/>
<xacro:property name="thigh_izz" value="0.000740309489"/>
<!-- calf -->
<xacro:property name="calf_mass" value="0.135862"/>
<xacro:property name="calf_com_x" value="0.006197"/>
<xacro:property name="calf_com_y" value="0.001408"/>
<xacro:property name="calf_com_z" value="-0.116695"/>
<xacro:property name="calf_ixx" value="0.001088793059"/>
<xacro:property name="calf_ixy" value="-0.000000255679"/>
<xacro:property name="calf_ixz" value="0.000007117814"/>
<xacro:property name="calf_iyy" value="0.001100428748"/>
<xacro:property name="calf_iyz" value="0.000002077264"/>
<xacro:property name="calf_izz" value="0.000024787446"/>
<!-- foot -->
<xacro:property name="foot_mass" value="0.06"/>
<gazebo reference="trunk">
2024-09-20 15:29:44 +08:00
<visual name="DarkGrey">
<material>
<ambient>.5 .5 .5 1.0</ambient>
<diffuse>.5 .5 .5 1.0</diffuse>
<specular>.5 .5 .5 1.0</specular>
</material>
</visual>
</gazebo>
2024-09-09 22:18:19 +08:00
</robot>