turtlebot_kinect.urdf.xacro 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  1. <?xml version="1.0"?>
  2. <robot name="turtlebot_kinect" xmlns:xacro="http://ros.org/wiki/xacro">
  3. <property name="M_PI" value="3.14159"/>
  4. <property name="MESH_SCALE" value="100"/>
  5. <xacro:include filename="$(find rbx1_description)/urdf/gazebo.urdf.xacro"/>
  6. <xacro:include filename="$(find rbx1_description)/urdf/turtlebot_calibration.xacro" />
  7. <xacro:macro name="turtlebot_kinect">
  8. <joint name="base_camera_joint" type="fixed">
  9. <origin xyz="${turtlebot_calib_cam_x} ${turtlebot_calib_cam_y} ${turtlebot_calib_cam_z}"
  10. rpy="${turtlebot_calib_cam_rr} ${turtlebot_calib_cam_rp} ${turtlebot_calib_cam_ry}" />
  11. <parent link="${turtlebot_camera_parent_name}" />
  12. <child link="camera_link" />
  13. </joint>
  14. <link name="camera_link">
  15. <inertial>
  16. <mass value="0.01" />
  17. <origin xyz="0 0 0" />
  18. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  19. iyy="0.001" iyz="0.0"
  20. izz="0.001" />
  21. </inertial>
  22. <visual>
  23. <origin xyz=" 0 0 0 " rpy="0 0 0" />
  24. <geometry>
  25. <mesh filename="package://rbx1_description/meshes/kinect.dae" scale="${MESH_SCALE} ${MESH_SCALE} ${MESH_SCALE}"/>
  26. </geometry>
  27. </visual>
  28. <collision>
  29. <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
  30. <geometry>
  31. <box size="0.0730 .2760 0.0720"/>
  32. </geometry>
  33. </collision>
  34. </link>
  35. <joint name="camera_depth_joint" type="fixed">
  36. <origin xyz="0 0.018 0" rpy="0 0 0" />
  37. <parent link="camera_link" />
  38. <child link="camera_depth_frame" />
  39. </joint>
  40. <link name="camera_depth_frame">
  41. <inertial>
  42. <mass value="0.01" />
  43. <origin xyz="0 0 0" />
  44. <inertia ixx="0.001" ixy="0.0" ixz="0.0"
  45. iyy="0.001" iyz="0.0"
  46. izz="0.001" />
  47. </inertial>
  48. </link>
  49. <joint name="camera_depth_optical_joint" type="fixed">
  50. <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
  51. <parent link="camera_depth_frame" />
  52. <child link="camera_depth_optical_frame" />
  53. </joint>
  54. <link name="camera_depth_optical_frame">
  55. <inertial>
  56. <mass value="0.001" />
  57. <origin xyz="0 0 0" />
  58. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  59. iyy="0.0001" iyz="0.0"
  60. izz="0.0001" />
  61. </inertial>
  62. </link>
  63. <joint name="camera_rgb_joint" type="fixed">
  64. <origin xyz="0 -0.005 0" rpy="0 0 0" />
  65. <parent link="camera_link" />
  66. <child link="camera_rgb_frame" />
  67. </joint>
  68. <link name="camera_rgb_frame">
  69. <inertial>
  70. <mass value="0.001" />
  71. <origin xyz="0 0 0" />
  72. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  73. iyy="0.0001" iyz="0.0"
  74. izz="0.0001" />
  75. </inertial>
  76. </link>
  77. <joint name="camera_rgb_optical_joint" type="fixed">
  78. <origin xyz="0 0 0" rpy="${-M_PI/2} 0 ${-M_PI/2}" />
  79. <parent link="camera_rgb_frame" />
  80. <child link="camera_rgb_optical_frame" />
  81. </joint>
  82. <link name="camera_rgb_optical_frame">
  83. <inertial>
  84. <mass value="0.001" />
  85. <origin xyz="0 0 0" />
  86. <inertia ixx="0.0001" ixy="0.0" ixz="0.0"
  87. iyy="0.0001" iyz="0.0"
  88. izz="0.0001" />
  89. </inertial>
  90. </link>
  91. <!-- Kinect sensor for simulation -->
  92. <turtlebot_sim_kinect/>
  93. </xacro:macro>
  94. </robot>