drz_telemax_base.urdf.xacro 3.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071
  1. <?xml version="1.0"?>
  2. <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  3. <xacro:property name="M_PI" value="3.1415926535897931" />
  4. <xacro:include filename="$(find drz_telemax_description)/urdf/drz_telemax_flipper.urdf.xacro"/>
  5. <xacro:include filename="$(find drz_telemax_description)/urdf/drz_telemax_base.gazebo.xacro"/>
  6. <xacro:include filename="$(find hector_xacro_tools)/urdf/inertia_tensors.urdf.xacro" />
  7. <xacro:property name="telemax_chassis_width" value="0.27" />
  8. <xacro:property name="telemax_chassis_length" value="0.65" />
  9. <xacro:property name="telemax_chassis_height" value="0.2" />
  10. <xacro:property name="telemax_flipper_x_offset" value="0.205"/>
  11. <xacro:property name="telemax_flipper_y_offset" value="0.17"/>
  12. <xacro:property name="telemax_flipper_z_offset" value="0.085"/>
  13. <xacro:macro name="telemax_base">
  14. <link name="base_link"/>
  15. <joint name="chassis_joint" type="fixed">
  16. <origin xyz="0 0 0" rpy="0 0 0" />
  17. <parent link="base_link"/>
  18. <child link="chassis_link" />
  19. </joint>
  20. <!-- robot chassis link -->
  21. <link name="chassis_link">
  22. <xacro:inertial_cuboid_with_pose mass="40" x_length="${telemax_chassis_length}" y_length="${telemax_chassis_width}" z_length="${telemax_chassis_height}" >
  23. <origin xyz="0 0 0.05" rpy="0 0 0"/>
  24. </xacro:inertial_cuboid_with_pose>
  25. <visual>
  26. <origin xyz="0 0 0" rpy="0 0 0"/>
  27. <geometry>
  28. <mesh filename="package://drz_telemax_description/meshes/maxpro_chassis.dae" scale="0.001 0.001 0.001"/>
  29. </geometry>
  30. </visual>
  31. <visual>
  32. <origin xyz="-0.125 0.0 0.225" rpy="0 0 0"/>
  33. <geometry>
  34. <mesh filename="package://drz_telemax_description/meshes/battery.dae" scale="0.001 0.001 0.001"/>
  35. </geometry>
  36. </visual>
  37. <collision>
  38. <origin xyz="0 0 0.105" rpy="0 0 0"/>
  39. <geometry>
  40. <box size="${telemax_chassis_length} ${telemax_chassis_width} ${telemax_chassis_height}"/>
  41. </geometry>
  42. </collision>
  43. </link>
  44. <xacro:telemax_flipper name="flipper_front_left" parent="chassis_link" front="1" left="1">
  45. <origin xyz="${telemax_flipper_x_offset} ${telemax_flipper_y_offset} ${telemax_flipper_z_offset}" rpy="0 0 0"/>
  46. </xacro:telemax_flipper>
  47. <xacro:telemax_flipper name="flipper_front_right" parent="chassis_link" front="1" left="-1">
  48. <origin xyz="${telemax_flipper_x_offset} ${-1 * telemax_flipper_y_offset} ${telemax_flipper_z_offset}" rpy="0 0 0"/>
  49. </xacro:telemax_flipper>
  50. <xacro:telemax_flipper name="flipper_back_left" parent="chassis_link" front="-1" left="1">
  51. <origin xyz="${-1 * telemax_flipper_x_offset} ${telemax_flipper_y_offset} ${telemax_flipper_z_offset}" rpy="0 0 ${M_PI}"/>
  52. </xacro:telemax_flipper>
  53. <xacro:telemax_flipper name="flipper_back_right" parent="chassis_link" front="-1" left="-1">
  54. <origin xyz="${-1 * telemax_flipper_x_offset} ${-1 * telemax_flipper_y_offset} ${telemax_flipper_z_offset}" rpy="0 0 ${M_PI}"/>
  55. </xacro:telemax_flipper>
  56. <!-- Gazebo plugins -->
  57. <xacro:telemax_base_gazebo_plugins/>
  58. <xacro:tracked_vehicle_gazebo_plugin tracks_separation="${2* telemax_flipper_y_offset}"/>
  59. <xacro:gazebo_ros_control_plugin/>
  60. </xacro:macro>
  61. </robot>