pi_robot_arm_hardware.xacro 7.3 KB

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