generic_stereo_camera.urdf.xacro 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117
  1. <?xml version="1.0"?>
  2. <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  3. <xacro:property name="M_PI" value="3.1415926535897931" />
  4. <xacro:macro name="generic_stereo_camera" params="name parent *origin ros_topic cam_info_topic update_rate res_x res_y image_format hfov baseline">
  5. <!-- Stereo Camera -->
  6. <joint name="${name}_left_camera_frame_joint" type="fixed">
  7. <!-- optical frame collocated with tilting DOF -->
  8. <xacro:insert_block name="origin" />
  9. <parent link="${parent}"/>
  10. <child link="${name}_left_camera_frame"/>
  11. </joint>
  12. <link name="${name}_left_camera_frame">
  13. <!-- <inertial>
  14. <mass value="1e-5" />
  15. <origin xyz="-0.075493 0.035033383 0.02574"/>
  16. <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
  17. </inertial>-->
  18. </link>
  19. <joint name="${name}_left_camera_optical_frame_joint" type="fixed">
  20. <origin xyz="0 0 0" rpy="-1.5708 0.0 -1.5708" />
  21. <parent link="${name}_left_camera_frame" />
  22. <child link="${name}_left_camera_optical_frame"/>
  23. </joint>
  24. <link name="${name}_left_camera_optical_frame"/>
  25. <gazebo reference="${name}_left_camera_frame">
  26. <sensor type="multicamera" name="stereo_camera">
  27. <!-- see MultiSenseSLPlugin.h for available modes -->
  28. <update_rate>30.0</update_rate>
  29. <camera name="left">
  30. <!-- Spec sheet says 80deg X 45deg @ 1024x544pix. Based on feedback
  31. from teams, we're instead doing 80deg X 80deg @ 800x800pix. -->
  32. <horizontal_fov>1.3962634</horizontal_fov>
  33. <image>
  34. <width>800</width>
  35. <height>800</height>
  36. <format>R8G8B8</format>
  37. </image>
  38. <clip>
  39. <near>0.02</near>
  40. <far>300</far>
  41. </clip>
  42. <noise>
  43. <type>gaussian</type>
  44. <!-- Noise is sampled independently per pixel on each frame.
  45. That pixel's noise value is added to each of its color
  46. channels, which at that point lie in the range [0,1].
  47. The stddev value of 0.007 is based on experimental data
  48. from a camera in a Sandia hand pointed at a static scene
  49. in a couple of different lighting conditions. -->
  50. <mean>0.0</mean>
  51. <stddev>0.007</stddev>
  52. </noise>
  53. </camera>
  54. <camera name="right">
  55. <pose>0 ${-baseline} 0 0 0 0</pose>
  56. <!-- Spec sheet says 80deg X 45deg @ 1024x544pix. Based on feedback
  57. from teams, we're instead doing 80deg X 80deg @ 800x800pix. -->
  58. <horizontal_fov>1.3962634</horizontal_fov>
  59. <image>
  60. <width>800</width>
  61. <height>800</height>
  62. <format>R8G8B8</format>
  63. </image>
  64. <clip>
  65. <near>0.02</near>
  66. <far>300</far>
  67. </clip>
  68. <noise>
  69. <type>gaussian</type>
  70. <!-- Noise is sampled independently per pixel on each frame.
  71. That pixel's noise value is added to each of its color
  72. channels, which at that point lie in the range [0,1].
  73. The stddev value of 0.007 is based on experimental data
  74. from a camera in a Sandia hand pointed at a static scene
  75. in a couple of different lighting conditions. -->
  76. <mean>0.0</mean>
  77. <stddev>0.007</stddev>
  78. </noise>
  79. </camera>
  80. <plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
  81. <cameraName>${name}</cameraName>
  82. <imageTopicName>image_raw</imageTopicName>
  83. <cameraInfoTopicName>camera_info</cameraInfoTopicName>
  84. <frameName>${name}_left_camera_optical_frame</frameName>
  85. <!--<rightFrameName>right_camera_optical_frame</rightFrameName>-->
  86. <hackBaseline>${baseline}</hackBaseline>
  87. </plugin>
  88. </sensor>
  89. </gazebo>
  90. <joint name="${name}_right_camera_frame_joint" type="fixed">
  91. <origin xyz="0.0 ${-baseline} -0.0"/>
  92. <parent link="${name}_left_camera_frame"/>
  93. <child link="${name}_right_camera_frame"/>
  94. </joint>
  95. <link name="${name}_right_camera_frame">
  96. <!-- <inertial>
  97. <mass value="1e-5" />
  98. <origin xyz="-0.075493 -0.034966617 0.02574"/>
  99. <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
  100. </inertial>-->
  101. </link>
  102. <joint name="${name}_right_camera_optical_frame_joint" type="fixed">
  103. <origin xyz="0 0 0" rpy="-1.5708 0.0 -1.5708" />
  104. <parent link="${name}_right_camera_frame" />
  105. <child link="${name}_right_camera_optical_frame"/>
  106. </joint>
  107. <link name="${name}_right_camera_optical_frame"/>
  108. </xacro:macro>
  109. </robot>