head_hardware.xacro 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182
  1. <?xml version="1.0"?>
  2. <robot name="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="F2_HEIGHT" value="0.0265"/>
  11. <property name="MESH_EXT" value="dae"/>
  12. <macro name="bioloid_F10_fixed" params="parent number x_loc y_loc z_loc color">
  13. <joint name="bioloid_F10_${number}_joint" type="fixed">
  14. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  15. <parent link="${parent}"/>
  16. <child link="bioloid_F10_${number}_link" />
  17. </joint>
  18. <link name="bioloid_F10_${number}_link">
  19. <inertial>
  20. <mass value="0.00001" />
  21. <origin xyz="0 0 0" />
  22. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  23. iyy="1.0" iyz="0.0"
  24. izz="1.0" />
  25. </inertial>
  26. <visual>
  27. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  28. <geometry>
  29. <mesh filename="package://rbx1_description/meshes/F10.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  30. </geometry>
  31. <material name="${color}"/>
  32. </visual>
  33. <collision>
  34. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  35. <geometry>
  36. <box size="0.025 0.038 0.004"/>
  37. </geometry>
  38. </collision>
  39. </link>
  40. </macro>
  41. <macro name="bioloid_F3_fixed" params="parent number x_loc y_loc z_loc r p y color">
  42. <joint name="bioloid_F3_${number}_joint" type="fixed">
  43. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  44. <parent link="${parent}"/>
  45. <child link="bioloid_F3_head_${number}_link" />
  46. </joint>
  47. <link name="bioloid_F3_${number}_link">
  48. <inertial>
  49. <mass value="0.00001" />
  50. <origin xyz="0 0 0" />
  51. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  52. iyy="1.0" iyz="0.0"
  53. izz="1.0" />
  54. </inertial>
  55. <visual>
  56. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  57. <geometry>
  58. <mesh filename="package://rbx1_description/meshes/F3.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  59. </geometry>
  60. <material name="${color}"/>
  61. </visual>
  62. <collision>
  63. <origin xyz="0.0 0.0 -0.0045" rpy="0 0 0" />
  64. <geometry>
  65. <box size="0.025 0.038 0.009"/>
  66. </geometry>
  67. </collision>
  68. </link>
  69. </macro>
  70. <macro name="dynamixel_AX12_fixed" params="parent number x_loc y_loc z_loc r p y">
  71. <joint name="dynamixel_AX12_${number}_joint" type="fixed">
  72. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  73. <parent link="${parent}"/>
  74. <child link="dynamixel_AX12_${number}_link" />
  75. </joint>
  76. <link name="dynamixel_AX12_${number}_link">
  77. <inertial>
  78. <mass value="0.00001" />
  79. <origin xyz="0 0 0" />
  80. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  81. iyy="1.0" iyz="0.0"
  82. izz="1.0" />
  83. </inertial>
  84. <visual>
  85. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  86. <geometry>
  87. <mesh filename="package://rbx1_description/meshes/ax12_box.${MESH_EXT}" scale="1 1 1"/>
  88. </geometry>
  89. <material name="black"/>
  90. </visual>
  91. <collision>
  92. <origin xyz="0.0 0.0 -0.0045" rpy="0 0 0" />
  93. <geometry>
  94. <box size="0.025 0.038 0.009"/>
  95. </geometry>
  96. </collision>
  97. </link>
  98. </macro>
  99. <macro name="bioloid_F3_head_revolute" params="parent number joint_name x_loc y_loc z_loc ulimit llimit r p y color">
  100. <joint name="${joint_name}_joint" type="revolute">
  101. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="${r} ${p} ${y}" />
  102. <parent link="${parent}"/>
  103. <axis xyz="0 0 -1"/>
  104. <limit effort="30" velocity="1.0" lower="${llimit}" upper="${ulimit}" />
  105. <child link="bioloid_F3_head_${number}_link" />
  106. </joint>
  107. <link name="bioloid_F3_head_${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="bioloid_F4_head_revolute" params="parent number joint_name x_loc y_loc z_loc ulimit llimit color">
  131. <joint name="${joint_name}_joint" type="revolute">
  132. <origin xyz="${x_loc} ${y_loc} ${z_loc}" rpy="0 0 0" />
  133. <parent link="${parent}"/>
  134. <axis xyz="0 -1 0"/>
  135. <limit effort="30" velocity="1.0" lower="${llimit}" upper="${ulimit}" />
  136. <child link="bioloid_F4_head_${number}_link" />
  137. </joint>
  138. <link name="bioloid_F4_head_${number}_link">
  139. <inertial>
  140. <mass value="0.00001" />
  141. <origin xyz="0 0 0" />
  142. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  143. iyy="1.0" iyz="0.0"
  144. izz="1.0" />
  145. </inertial>
  146. <visual>
  147. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  148. <geometry>
  149. <mesh filename="package://rbx1_description/meshes/F4.${MESH_EXT}" scale="${M_SCALE} ${M_SCALE} ${M_SCALE}"/>
  150. </geometry>
  151. <material name="${color}"/>
  152. </visual>
  153. <collision>
  154. <origin xyz="0.0 0.0 0.0215" rpy="0 0 0" />
  155. <geometry>
  156. <box size="0.028 0.0485 0.065"/>
  157. </geometry>
  158. </collision>
  159. </link>
  160. </macro>
  161. </robot>