head.xacro 6.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199
  1. <?xml version="1.0"?>
  2. <robot name="head" xmlns:xacro="http://ros.org/wiki/xacro">
  3. <property name="MESH_SCALE" value="100"/>
  4. <xacro:include filename="$(find rbx1_description)/urdf/head_hardware.xacro" />
  5. <macro name="turtlebot_head" params="parent color *origin">
  6. <link name="head_base_link" />
  7. <joint name="head_base_joint" type="fixed">
  8. <insert_block name="origin" />
  9. <parent link="${parent}"/>
  10. <child link="head_base_link" />
  11. </joint>
  12. <!-- fake head_pan_link joint -->
  13. <link name="head_pan_link" />
  14. <joint name="fake_head_pan_joint" type="fixed">
  15. <origin xyz="0 0 0" rpy="0 ${M_PI/2} ${M_PI/2}" />
  16. <parent link="dynamixel_AX12_10_link"/>
  17. <child link="head_pan_link" />
  18. </joint>
  19. <!-- fake head_tilt_link joint -->
  20. <link name="head_tilt_link" />
  21. <joint name="fake_head_tilt_joint" type="fixed">
  22. <origin xyz="0 0 0" rpy="0 0 ${M_PI}" />
  23. <parent link="dynamixel_AX12_11_link"/>
  24. <child link="head_tilt_link" />
  25. </joint>
  26. <!-- head base plate (needed for collision awareness) -->
  27. <arm_head_base_plate parent="plate_3_link" number="1" x_loc="-0.027" y_loc="-0.0175" z_loc="0.075" color="green"/>
  28. <!-- head pan joint -->
  29. <dynamixel_AX12_fixed parent="head_base_link" number="10" x_loc="0" y_loc="0" z_loc="${-AX12_WIDTH/2}" r="${M_PI/2}" p="0" y="${-M_PI/2}"/>
  30. <bioloid_F3_head_revolute parent="dynamixel_AX12_10_link" number="10" joint_name="head_pan" x_loc="0" y_loc="${AX12_WIDTH/2 + 0.005}" z_loc="0.0" ulimit="2.9" llimit="-2.9" r="${-M_PI/2}" p="${M_PI/2}" y="${M_PI}" color="${color}"/>
  31. <dynamixel_AX12_fixed parent="bioloid_F3_head_10_link" number="11" x_loc="0" y_loc="0" z_loc="${-AX12_HEIGHT-F10_HEIGHT+0.001}" r="0" p="${M_PI}" y="0"/>
  32. <!--head tilt joint -->
  33. <bioloid_F4_head_revolute parent="dynamixel_AX12_11_link" number="10" joint_name="head_tilt" x_loc="0" y_loc="0" z_loc="0" ulimit="2.9" llimit="-2.9" color="${color}"/>
  34. <bioloid_F10_fixed parent="bioloid_F4_head_10_link" number="10" x_loc="0" y_loc="0" z_loc="${F4_HEIGHT + F10_HEIGHT/2}" color="${color}"/>
  35. <joint name="base_camera_joint" type="fixed">
  36. <origin xyz="-0.03 0 0.058" rpy="0 0 ${M_PI}" />
  37. <parent link="bioloid_F10_10_link" />
  38. <child link="camera_link" />
  39. </joint>
  40. <link name="camera_link">
  41. <inertial>
  42. <mass value="0.00001" />
  43. <origin xyz="0 0 0" />
  44. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  45. iyy="1.0" iyz="0.0"
  46. izz="1.0" />
  47. </inertial>
  48. <visual>
  49. <origin xyz="0 0 0 " rpy="0 0 0" />
  50. <geometry>
  51. <mesh filename="package://rbx1_description/meshes/kinect.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  52. </geometry>
  53. </visual>
  54. <collision>
  55. <origin xyz="-0.0275 0.0 0.0" rpy="0 0 0" />
  56. <geometry>
  57. <box size="0.0730 .2760 0.0720"/>
  58. </geometry>
  59. </collision>
  60. </link>
  61. <joint name="camera_depth_joint" type="fixed">
  62. <origin xyz="0 0.018 0" rpy="0 0 0" />
  63. <parent link="camera_link" />
  64. <child link="camera_depth_frame" />
  65. </joint>
  66. <link name="camera_depth_frame">
  67. <inertial>
  68. <mass value="0.000001" />
  69. <origin xyz="0 0 0" />
  70. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  71. iyy="0.0001" iyz="0.0"
  72. izz="0.0001" />
  73. </inertial>
  74. </link>
  75. <joint name="camera_depth_optical_joint" type="fixed">
  76. <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
  77. <parent link="camera_depth_frame" />
  78. <child link="camera_depth_optical_frame" />
  79. </joint>
  80. <link name="camera_depth_optical_frame">
  81. <inertial>
  82. <mass value="0.000001" />
  83. <origin xyz="0 0 0" />
  84. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  85. iyy="0.0001" iyz="0.0"
  86. izz="0.0001" />
  87. </inertial>
  88. </link>
  89. <joint name="camera_rgb_joint" type="fixed">
  90. <origin xyz="0 -0.005 0" rpy="0 0 0" />
  91. <parent link="camera_link" />
  92. <child link="camera_rgb_frame" />
  93. </joint>
  94. <link name="camera_rgb_frame">
  95. <inertial>
  96. <mass value="0.000001" />
  97. <origin xyz="0 0 0" />
  98. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  99. iyy="0.0001" iyz="0.0"
  100. izz="0.0001" />
  101. </inertial>
  102. </link>
  103. <joint name="camera_rgb_optical_joint" type="fixed">
  104. <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
  105. <parent link="camera_rgb_frame" />
  106. <child link="camera_rgb_optical_frame" />
  107. </joint>
  108. <link name="camera_rgb_optical_frame">
  109. <inertial>
  110. <mass value="0.000001" />
  111. <origin xyz="0 0 0" />
  112. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  113. iyy="0.0001" iyz="0.0"
  114. izz="0.0001" />
  115. </inertial>
  116. </link>
  117. <link name="left_eye_link">
  118. <visual>
  119. <origin xyz="0 0 0" rpy="0 1.57 0" />
  120. <geometry>
  121. <cylinder length="0.01" radius="0.01" />
  122. </geometry>
  123. <material name="OffWhite" />
  124. </visual>
  125. <collision>
  126. <origin xyz="0 0 0" rpy="0 1.57 0" />
  127. <geometry>
  128. <cylinder length="0.01" radius="0.01" />
  129. </geometry>
  130. </collision>
  131. <inertial>
  132. <mass value="0.00001" />
  133. <origin xyz="0 0 0" />
  134. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  135. iyy="1.0" iyz="0.0"
  136. izz="1.0" />
  137. </inertial>
  138. </link>
  139. <link name="right_eye_link">
  140. <visual>
  141. <origin xyz="0 0 0" rpy="0 1.57 0" />
  142. <geometry>
  143. <cylinder length="0.01" radius="0.01" />
  144. </geometry>
  145. <material name="OffWhite" />
  146. </visual>
  147. <collision>
  148. <origin xyz="0 0 0" rpy="0 1.57 0" />
  149. <geometry>
  150. <cylinder length="0.01" radius="0.01" />
  151. </geometry>
  152. </collision>
  153. <inertial>
  154. <mass value="0.00001" />
  155. <origin xyz="0 0 0" />
  156. <inertia ixx="1.0" ixy="0.0" ixz="0.0"
  157. iyy="1.0" iyz="0.0"
  158. izz="1.0" />
  159. </inertial>
  160. </link>
  161. <joint name="left_eye_joint" type="fixed">
  162. <parent link="camera_link" />
  163. <child link="left_eye_link" />
  164. <origin xyz="-0.005 0.035 0" rpy="0 0 0" />
  165. </joint>
  166. <joint name="right_eye_joint" type="fixed">
  167. <parent link="camera_link" />
  168. <child link="right_eye_link" />
  169. <origin xyz="-0.005 -0.035 0" rpy="0 0 0" />
  170. </joint>
  171. </macro>
  172. </robot>