kinect_camera.urdf.xacro 3.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495
  1. <?xml version="1.0"?>
  2. <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  3. <xacro:include filename="$(find hector_xacro_tools)/urdf/inertia_tensors.urdf.xacro"/>
  4. <xacro:property name="M_PI" value="3.1415926535897931" />
  5. <xacro:macro name="kinect_camera_model" params="name parent *origin">
  6. <joint name="${name}_joint" type="fixed">
  7. <xacro:insert_block name="origin" />
  8. <parent link="${parent}"/>
  9. <child link="${name}_link"/>
  10. </joint>
  11. <link name="${name}_link">
  12. <xacro:inertial_sphere mass="0.01" diameter="0.07" />
  13. <visual>
  14. <origin xyz="0 0 0" rpy="0 0 0" />
  15. <geometry>
  16. <mesh filename="package://hector_sensors_description/meshes/kinect_camera/kinect_camera_simple.dae"/>
  17. </geometry>
  18. </visual>
  19. <collision>
  20. <origin xyz="0 0 0" rpy="0 0 0" />
  21. <geometry>
  22. <mesh filename="package://hector_sensors_description/meshes/kinect_camera/kinect_camera_simple.stl"/>
  23. </geometry>
  24. </collision>
  25. </link>
  26. <joint name="${name}_depth_joint" type="fixed">
  27. <origin xyz="0.0 -0.02 0.0" rpy="0 0 0" />
  28. <parent link="${name}_link" />
  29. <child link="${name}_depth_frame"/>
  30. </joint>
  31. <link name="${name}_depth_frame"/>
  32. <joint name="${name}_depth_optical_joint" type="fixed">
  33. <origin xyz="0 0 0" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" />
  34. <parent link="${name}_depth_frame" />
  35. <child link="${name}_depth_optical_frame"/>
  36. </joint>
  37. <link name="${name}_depth_optical_frame"/>
  38. <joint name="${name}_rgb_joint" type="fixed">
  39. <origin xyz="0.0 -0.0125 0.0" rpy="0 0 0" />
  40. <parent link="${name}_link" />
  41. <child link="${name}_rgb_frame"/>
  42. </joint>
  43. <link name="${name}_rgb_frame"/>
  44. <joint name="${name}_rgb_optical_joint" type="fixed">
  45. <origin xyz="0 0 0" rpy="${-M_PI/2} 0.0 ${-M_PI/2}" />
  46. <parent link="${name}_rgb_frame" />
  47. <child link="${name}_rgb_optical_frame"/>
  48. </joint>
  49. <link name="${name}_rgb_optical_frame"/>
  50. </xacro:macro>
  51. <xacro:macro name="kinect_camera" params="name parent *origin">
  52. <xacro:kinect_camera_model name="${name}" parent="${parent}">
  53. <xacro:insert_block name="origin" />
  54. </xacro:kinect_camera_model>
  55. <gazebo reference="${name}_depth_frame">
  56. <sensor type="depth" name="${name}">
  57. <update_rate>20</update_rate>
  58. <camera>
  59. <horizontal_fov>${60 * M_PI/180.0}</horizontal_fov>
  60. <image>
  61. <format>B8G8R8</format>
  62. <width>640</width>
  63. <height>480</height>
  64. </image>
  65. <clip>
  66. <near>0.05</near>
  67. <far>3</far>
  68. </clip>
  69. </camera>
  70. <plugin name="${name}_camera_controller" filename="libgazebo_ros_openni_kinect.so">
  71. <imageTopicName>${name}/rgb/image_raw</imageTopicName>
  72. <cameraInfoTopicName>${name}/rgb/camera_info</cameraInfoTopicName>
  73. <depthImageTopicName>${name}/depth/image_raw</depthImageTopicName>
  74. <depthImageCameraInfoTopicName>${name}/depth/camera_info</depthImageCameraInfoTopicName>
  75. <pointCloudTopicName>${name}/depth/points</pointCloudTopicName>
  76. <frameName>${name}_depth_optical_frame</frameName>
  77. </plugin>
  78. </sensor>
  79. </gazebo>
  80. </xacro:macro>
  81. </robot>