arm_hardware.xacro 8.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285
  1. <?xml version="1.0"?>
  2. <robot name="arm_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. <property name="MESH_SCALE" value="100"/>
  6. <property name="F10_HEIGHT" value="0.004"/>
  7. <property name="F4_HEIGHT" value="0.0525"/>
  8. <property name="F3_HEIGHT" value="0.009"/>
  9. <property name="AX12_HEIGHT" value="0.0385"/>
  10. <property name="AX12_WIDTH" value="0.038"/>
  11. <property name="AX12_DEPTH" value="0.048"/>
  12. <property name="F2_HEIGHT" value="0.0265"/>
  13. <property name="MESH_EXT" value="dae"/>
  14. <macro name="arm_head_base_plate" params="parent number x_loc y_loc z_loc color">
  15. <joint name="arm_head_base_plate_${number}_joint" type="fixed">
  16. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  17. <parent link="${parent}"/>
  18. <child link="arm_head_base_plate_${number}_link" />
  19. </joint>
  20. <link name="arm_head_base_plate_${number}_link">
  21. <inertial>
  22. <mass value="0.00001" />
  23. <origin xyz="0 0 0" />
  24. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  25. iyy="1.0" iyz="0.0"
  26. izz="1.0" />
  27. </inertial>
  28. <visual>
  29. <origin xyz="0 0 0" rpy="0 0 0" />
  30. <geometry>
  31. <mesh filename="package://rbx1_description/meshes/arm_head_base_plate.dae" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  32. </geometry>
  33. <material name="${color}"/>
  34. </visual>
  35. <collision>
  36. <origin xyz="-0.045 0.0175 0" rpy="0 0 0" />
  37. <geometry>
  38. <box size="0.08 0.08 0.01"/>
  39. </geometry>
  40. </collision>
  41. </link>
  42. </macro>
  43. <macro name="bioloid_F10_fixed" params="parent number x_loc y_loc z_loc color">
  44. <joint name="bioloid_F10_${number}_joint" type="fixed">
  45. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  46. <parent link="${parent}"/>
  47. <child link="bioloid_F10_${number}_link" />
  48. </joint>
  49. <link name="bioloid_F10_${number}_link">
  50. <inertial>
  51. <mass value="0.00001" />
  52. <origin xyz="0 0 0" />
  53. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  54. iyy="1.0" iyz="0.0"
  55. izz="1.0" />
  56. </inertial>
  57. <visual>
  58. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  59. <geometry>
  60. <mesh filename="package://rbx1_description/meshes/F10.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  61. </geometry>
  62. <material name="${color}"/>
  63. </visual>
  64. <collision>
  65. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  66. <geometry>
  67. <box size="0.025 0.038 0.004"/>
  68. </geometry>
  69. </collision>
  70. </link>
  71. </macro>
  72. <macro name="finger_fixed" params="parent number x_loc y_loc z_loc r p y color">
  73. <joint name="finger_${number}_joint" type="fixed">
  74. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  75. <parent link="${parent}"/>
  76. <child link="finger_${number}_link" />
  77. </joint>
  78. <link name="finger_${number}_link">
  79. <inertial>
  80. <mass value="0.00001" />
  81. <origin xyz="0 0 0" />
  82. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  83. iyy="1.0" iyz="0.0"
  84. izz="1.0" />
  85. </inertial>
  86. <visual>
  87. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  88. <geometry>
  89. <mesh filename="package://rbx1_description/meshes/finger.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  90. </geometry>
  91. <material name="${color}"/>
  92. </visual>
  93. <collision>
  94. <origin xyz="0.02645 0.0 -0.00655" rpy="0 0 0" />
  95. <geometry>
  96. <box size="0.0783 0.03801 0.0193"/>
  97. </geometry>
  98. </collision>
  99. </link>
  100. </macro>
  101. <macro name="bioloid_F3_fixed" params="parent number x_loc y_loc z_loc r p y color">
  102. <joint name="bioloid_F3_${number}_joint" type="fixed">
  103. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  104. <parent link="${parent}"/>
  105. <child link="bioloid_F3_${number}_link" />
  106. </joint>
  107. <link name="bioloid_F3_${number}_link">
  108. <inertial>
  109. <mass value="0.00001" />
  110. <origin xyz="0 0 0" />
  111. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  112. iyy="1.0" iyz="0.0"
  113. izz="1.0" />
  114. </inertial>
  115. <visual>
  116. <origin xyz="0 0 0 " rpy="0 0 0" />
  117. <geometry>
  118. <mesh filename="package://rbx1_description/meshes/F3.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  119. </geometry>
  120. <material name="${color}"/>
  121. </visual>
  122. <collision>
  123. <origin xyz="0.0 0.0 -0.0045" rpy="0 0 0" />
  124. <geometry>
  125. <box size="0.025 0.038 0.009"/>
  126. </geometry>
  127. </collision>
  128. </link>
  129. </macro>
  130. <macro name="dynamixel_AX12_fixed" params="parent number x_loc y_loc z_loc r p y">
  131. <joint name="dynamixel_AX12_${number}_joint" type="fixed">
  132. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  133. <parent link="${parent}"/>
  134. <child link="dynamixel_AX12_${number}_link" />
  135. </joint>
  136. <link name="dynamixel_AX12_${number}_link">
  137. <inertial>
  138. <mass value="0.00001" />
  139. <origin xyz="0 0 0" />
  140. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  141. iyy="1.0" iyz="0.0"
  142. izz="1.0" />
  143. </inertial>
  144. <visual>
  145. <origin xyz="0 0 0 " rpy="0 0 0" />
  146. <geometry>
  147. <mesh filename="package://rbx1_description/meshes/ax12_box.${MESH_EXT}" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  148. </geometry>
  149. <material name="black"/>
  150. </visual>
  151. <collision>
  152. <origin xyz="0.0 0.0 -0.01241" rpy="0 0 0" />
  153. <geometry>
  154. <box size="0.025 0.038 0.04762"/>
  155. </geometry>
  156. </collision>
  157. </link>
  158. </macro>
  159. <macro name="bioloid_F3_revolute" params="parent number joint_name x_loc y_loc z_loc r p y color">
  160. <joint name="${joint_name}_joint" type="revolute">
  161. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  162. <parent link="${parent}"/>
  163. <axis xyz="0 0 -1"/>
  164. <limit effort="30" velocity="1.0" lower="-2.9" upper="2.9" />
  165. <child link="bioloid_F3_${number}_link" />
  166. </joint>
  167. <link name="bioloid_F3_${number}_link">
  168. <inertial>
  169. <mass value="0.00001" />
  170. <origin xyz="0 0 0" />
  171. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  172. iyy="1.0" iyz="0.0"
  173. izz="1.0" />
  174. </inertial>
  175. <visual>
  176. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  177. <geometry>
  178. <mesh filename="package://rbx1_description/meshes/F3.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  179. </geometry>
  180. <material name="${color}"/>
  181. </visual>
  182. <collision>
  183. <origin xyz="0.0 0.0 -0.0045" rpy="0 0 0" />
  184. <geometry>
  185. <box size="0.025 0.038 0.009"/>
  186. </geometry>
  187. </collision>
  188. </link>
  189. </macro>
  190. <macro name="bioloid_F2_revolute" params="parent number joint_name x_loc y_loc z_loc ulimit llimit color">
  191. <joint name="${joint_name}_joint" type="revolute">
  192. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  193. <parent link="${parent}"/>
  194. <axis xyz="0 1 0"/>
  195. <limit effort="30" velocity="1.0" lower="${llimit}" upper="${ulimit}" />
  196. <child link="bioloid_F2_${number}_link" />
  197. </joint>
  198. <link name="bioloid_F2_${number}_link">
  199. <inertial>
  200. <mass value="0.00001" />
  201. <origin xyz="0 0 0" />
  202. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  203. iyy="1.0" iyz="0.0"
  204. izz="1.0" />
  205. </inertial>
  206. <visual>
  207. <origin xyz="0 0 0 " rpy="0 0 0" />
  208. <geometry>
  209. <mesh filename="package://rbx1_description/meshes/F2.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  210. </geometry>
  211. <material name="${color}"/>
  212. </visual>
  213. <collision>
  214. <origin xyz="0.0 0.0 0.00775" rpy="0 0 0" />
  215. <geometry>
  216. <box size="0.025 0.0485 0.0375"/>
  217. </geometry>
  218. </collision>
  219. </link>
  220. </macro>
  221. <macro name="bioloid_F4_revolute" params="parent number joint_name x_loc y_loc z_loc color">
  222. <joint name="${joint_name}_joint" type="revolute">
  223. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  224. <parent link="${parent}"/>
  225. <axis xyz="0 1 0"/>
  226. <limit effort="30" velocity="1.0" lower="-2.9" upper="2.9" />
  227. <child link="bioloid_F4_${number}_link" />
  228. </joint>
  229. <link name="bioloid_F4_${number}_link">
  230. <inertial>
  231. <mass value="0.00001" />
  232. <origin xyz="0 0 0" />
  233. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  234. iyy="1.0" iyz="0.0"
  235. izz="1.0" />
  236. </inertial>
  237. <visual>
  238. <origin xyz="0 0 0 " rpy="0 0 0" />
  239. <geometry>
  240. <mesh filename="package://rbx1_description/meshes/F4.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  241. </geometry>
  242. <material name="${color}"/>
  243. </visual>
  244. <collision>
  245. <origin xyz="0.0 0.0 0.0215" rpy="0 0 0" />
  246. <geometry>
  247. <box size="0.028 0.0485 0.065"/>
  248. </geometry>
  249. </collision>
  250. </link>
  251. </macro>
  252. </robot>