turtlebot_hardware.urdf.xacro 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167
  1. <?xml version="1.0"?>
  2. <robot name="turtlebot_hardware" xmlns:xacro="http://ros.org/wiki/xacro">
  3. <property name="M_PI" value="3.14159"/>
  4. <property name="M_SCALE" value="0.001"/>
  5. <xacro:macro name="turtlebot_spacer" params="parent number x_loc y_loc z_loc">
  6. <joint name="spacer_${number}_joint" type="fixed">
  7. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  8. <parent link="${parent}"/>
  9. <child link="spacer_${number}_link" />
  10. </joint>
  11. <link name="spacer_${number}_link">
  12. <inertial>
  13. <mass value="0.001" />
  14. <origin xyz="0 0 0" />
  15. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  16. iyy="0.0001" iyz="0.0"
  17. izz="0.0001" />
  18. </inertial>
  19. <visual>
  20. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  21. <geometry>
  22. <mesh filename="package://rbx1_description/meshes/68-02403-125_Spacer.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  23. </geometry>
  24. </visual>
  25. <collision>
  26. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  27. <geometry>
  28. <cylinder length="0.003175" radius=".0127"/>
  29. </geometry>
  30. </collision>
  31. </link>
  32. </xacro:macro>
  33. <xacro:macro name="turtlebot_standoff_1in" params="parent number x_loc y_loc z_loc">
  34. <joint name="standoff_1in_${number}_joint" type="fixed">
  35. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  36. <parent link="${parent}"/>
  37. <child link="standoff_1in_${number}_link" />
  38. </joint>
  39. <link name="standoff_1in_${number}_link">
  40. <inertial>
  41. <mass value="0.001" />
  42. <origin xyz="0 0 0" />
  43. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  44. iyy="0.0001" iyz="0.0"
  45. izz="0.0001" />
  46. </inertial>
  47. <visual>
  48. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  49. <geometry>
  50. <mesh filename="package://rbx1_description/meshes/68-04552-1000-RA_Turtlebot_M-F_Standoff.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  51. </geometry>
  52. </visual>
  53. <collision>
  54. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  55. <geometry>
  56. <cylinder length="0.0381" radius="0.011113"/>
  57. </geometry>
  58. </collision>
  59. </link>
  60. </xacro:macro>
  61. <xacro:macro name="turtlebot_standoff_2in" params="parent number x_loc y_loc z_loc">
  62. <joint name="standoff_2in_${number}_joint" type="fixed">
  63. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  64. <parent link="${parent}"/>
  65. <child link="standoff_2in_${number}_link" />
  66. </joint>
  67. <link name="standoff_2in_${number}_link">
  68. <inertial>
  69. <mass value="0.001" />
  70. <origin xyz="0 0 0" />
  71. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  72. iyy="0.0001" iyz="0.0"
  73. izz="0.0001" />
  74. </inertial>
  75. <visual>
  76. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  77. <geometry>
  78. <mesh filename="package://rbx1_description/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  79. </geometry>
  80. </visual>
  81. <collision>
  82. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  83. <geometry>
  84. <cylinder length="0.0635" radius="0.0381"/>
  85. </geometry>
  86. </collision>
  87. </link>
  88. </xacro:macro>
  89. <xacro:macro name="turtlebot_standoff_8in" params="parent number x_loc y_loc z_loc">
  90. <joint name="standoff_8in_${number}_joint" type="fixed">
  91. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  92. <parent link="${parent}"/>
  93. <child link="standoff_8in_${number}_link" />
  94. </joint>
  95. <link name="standoff_8in_${number}_link">
  96. <inertial>
  97. <mass value="0.001" />
  98. <origin xyz="0 0 0" />
  99. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  100. iyy="0.0001" iyz="0.0"
  101. izz="0.0001" />
  102. </inertial>
  103. <visual>
  104. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  105. <geometry>
  106. <mesh filename="package://rbx1_description/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  107. </geometry>
  108. </visual>
  109. <collision>
  110. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  111. <geometry>
  112. <cylinder length="0.2032" radius="0.011113"/>
  113. </geometry>
  114. </collision>
  115. </link>
  116. </xacro:macro>
  117. <xacro:macro name="turtlebot_standoff_kinect" params="parent number x_loc y_loc z_loc">
  118. <joint name="standoff_kinect_${number}_joint" type="fixed">
  119. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  120. <parent link="${parent}"/>
  121. <child link="standoff_kinect_${number}_link" />
  122. </joint>
  123. <link name="standoff_kinect_${number}_link">
  124. <inertial>
  125. <mass value="0.001" />
  126. <origin xyz="0 0 0" />
  127. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  128. iyy="0.0001" iyz="0.0"
  129. izz="0.0001" />
  130. </inertial>
  131. <visual>
  132. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  133. <geometry>
  134. <mesh filename="package://rbx1_description/meshes/68-04556-RA_Kinect_Standoff_Assy.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  135. </geometry>
  136. </visual>
  137. <collision>
  138. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  139. <geometry>
  140. <cylinder length="0.008585" radius="0.001111"/>
  141. </geometry>
  142. </collision>
  143. </link>
  144. </xacro:macro>
  145. </robot>