pi_robot_head_hardware.xacro 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184
  1. <?xml version="1.0"?>
  2. <robot name="pi_robot_head_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="F10_HEIGHT" value="0.004"/>
  6. <property name="F4_HEIGHT" value="0.0525"/>
  7. <property name="F3_HEIGHT" value="0.009"/>
  8. <property name="AX12_HEIGHT" value="0.0385"/>
  9. <property name="AX12_WIDTH" value="0.038"/>
  10. <property name="AX12_DEPTH" value="0.048"/>
  11. <property name="F2_HEIGHT" value="0.0265"/>
  12. <property name="MESH_EXT" value="dae"/>
  13. <property name="MESH_SCALE" value="100"/>
  14. <macro name="bioloid_F10_fixed" params="parent number x_loc y_loc z_loc color">
  15. <joint name="bioloid_F10_${number}_joint" type="fixed">
  16. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  17. <parent link="${parent}"/>
  18. <child link="bioloid_F10_${number}_link" />
  19. </joint>
  20. <link name="bioloid_F10_${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/F10.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  32. </geometry>
  33. <material name="${color}"/>
  34. </visual>
  35. <collision>
  36. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  37. <geometry>
  38. <box size="0.025 0.038 0.004"/>
  39. </geometry>
  40. </collision>
  41. </link>
  42. </macro>
  43. <macro name="bioloid_F3_fixed" params="parent number x_loc y_loc z_loc r p y color">
  44. <joint name="bioloid_F3_${number}_joint" type="fixed">
  45. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  46. <parent link="${parent}"/>
  47. <child link="bioloid_F3_head_${number}_link" />
  48. </joint>
  49. <link name="bioloid_F3_${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/F3.${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.0045" rpy="0 0 0" />
  66. <geometry>
  67. <box size="0.025 0.038 0.009"/>
  68. </geometry>
  69. </collision>
  70. </link>
  71. </macro>
  72. <macro name="dynamixel_AX12_fixed" params="parent number x_loc y_loc z_loc r p y">
  73. <joint name="dynamixel_AX12_${number}_joint" type="fixed">
  74. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  75. <parent link="${parent}"/>
  76. <child link="dynamixel_AX12_${number}_link" />
  77. </joint>
  78. <link name="dynamixel_AX12_${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/ax12_box.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  90. </geometry>
  91. <material name="black"/>
  92. </visual>
  93. <collision>
  94. <origin xyz="0.0 0.0 -0.0045" rpy="0 0 0" />
  95. <geometry>
  96. <box size="0.025 0.038 0.009"/>
  97. </geometry>
  98. </collision>
  99. </link>
  100. </macro>
  101. <macro name="bioloid_F3_head_revolute" params="parent number joint_name x_loc y_loc z_loc ulimit llimit r p y color">
  102. <joint name="${joint_name}_joint" type="revolute">
  103. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  104. <parent link="${parent}"/>
  105. <axis xyz="0 0 -1"/>
  106. <limit effort="30" velocity="1.0" lower="${llimit}" upper="${ulimit}" />
  107. <child link="bioloid_F3_head_${number}_link" />
  108. </joint>
  109. <link name="bioloid_F3_head_${number}_link">
  110. <inertial>
  111. <mass value="0.00001" />
  112. <origin xyz="0 0 0" />
  113. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  114. iyy="1.0" iyz="0.0"
  115. izz="1.0" />
  116. </inertial>
  117. <visual>
  118. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  119. <geometry>
  120. <mesh filename="package://rbx1_description/meshes/F3.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  121. </geometry>
  122. <material name="${color}"/>
  123. </visual>
  124. <collision>
  125. <origin xyz="0.0 0.0 -0.0045" rpy="0 0 0" />
  126. <geometry>
  127. <box size="0.025 0.038 0.009"/>
  128. </geometry>
  129. </collision>
  130. </link>
  131. </macro>
  132. <macro name="bioloid_F4_head_revolute" params="parent number joint_name x_loc y_loc z_loc ulimit llimit color">
  133. <joint name="${joint_name}_joint" type="revolute">
  134. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  135. <parent link="${parent}"/>
  136. <axis xyz="0 -1 0"/>
  137. <limit effort="30" velocity="1.0" lower="${llimit}" upper="${ulimit}" />
  138. <child link="bioloid_F4_head_${number}_link" />
  139. </joint>
  140. <link name="bioloid_F4_head_${number}_link">
  141. <inertial>
  142. <mass value="0.00001" />
  143. <origin xyz="0 0 0" />
  144. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  145. iyy="1.0" iyz="0.0"
  146. izz="1.0" />
  147. </inertial>
  148. <visual>
  149. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  150. <geometry>
  151. <mesh filename="package://rbx1_description/meshes/F4.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  152. </geometry>
  153. <material name="${color}"/>
  154. </visual>
  155. <collision>
  156. <origin xyz="0.0 0.0 0.0215" rpy="0 0 0" />
  157. <geometry>
  158. <box size="0.028 0.0485 0.065"/>
  159. </geometry>
  160. </collision>
  161. </link>
  162. </macro>
  163. </robot>