127 lines
4.3 KiB
XML
127 lines
4.3 KiB
XML
<?xml version="1.0"?>
|
|
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
|
|
|
<xacro:macro name="realsense_gazebo" params="prefix">
|
|
<gazebo reference="${prefix}camera_depth_frame">
|
|
<sensor name="cameradepth" type="depth">
|
|
<camera name="camera">
|
|
<horizontal_fov>1.57</horizontal_fov>
|
|
<image>
|
|
<width>1280</width>
|
|
<height>720</height>
|
|
</image>
|
|
<clip>
|
|
<near>0.1</near>
|
|
<far>100</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.100</stddev>
|
|
</noise>
|
|
</camera>
|
|
<always_on>1</always_on>
|
|
<update_rate>30</update_rate>
|
|
<visualize>0</visualize>
|
|
</sensor>
|
|
</gazebo>
|
|
<gazebo reference="${prefix}camera_color_frame">
|
|
<sensor name="cameracolor" type="camera">
|
|
<camera name="camera">
|
|
<horizontal_fov>1.57</horizontal_fov>
|
|
<image>
|
|
<width>1280</width>
|
|
<height>720</height>
|
|
<format>RGB_INT8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.1</near>
|
|
<far>100</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.007</stddev>
|
|
</noise>
|
|
</camera>
|
|
<always_on>1</always_on>
|
|
<update_rate>30</update_rate>
|
|
<visualize>1</visualize>
|
|
</sensor>
|
|
</gazebo>
|
|
<gazebo reference="${prefix}camera_left_ir_frame">
|
|
<sensor name="cameraired1" type="camera">
|
|
<camera name="camera">
|
|
<horizontal_fov>1.57</horizontal_fov>
|
|
<image>
|
|
<width>1280</width>
|
|
<height>720</height>
|
|
<format>L_INT8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.1</near>
|
|
<far>100</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.05</stddev>
|
|
</noise>
|
|
</camera>
|
|
<always_on>1</always_on>
|
|
<update_rate>1</update_rate>
|
|
<visualize>0</visualize>
|
|
</sensor>
|
|
</gazebo>
|
|
<gazebo reference="${prefix}camera_right_ir_frame">
|
|
<sensor name="cameraired2" type="camera">
|
|
<camera name="camera">
|
|
<horizontal_fov>1.57</horizontal_fov>
|
|
<image>
|
|
<width>1280</width>
|
|
<height>720</height>
|
|
<format>L_INT8</format>
|
|
</image>
|
|
<clip>
|
|
<near>0.1</near>
|
|
<far>100</far>
|
|
</clip>
|
|
<noise>
|
|
<type>gaussian</type>
|
|
<mean>0.0</mean>
|
|
<stddev>0.05</stddev>
|
|
</noise>
|
|
</camera>
|
|
<always_on>1</always_on>
|
|
<update_rate>1</update_rate>
|
|
<visualize>0</visualize>
|
|
</sensor>
|
|
</gazebo>
|
|
<gazebo>
|
|
<plugin name="realsense_gazebo_camera" filename="librealsense_gazebo_plugin.so">
|
|
<prefix>camera</prefix>
|
|
<depthUpdateRate>30.0</depthUpdateRate>
|
|
<colorUpdateRate>30.0</colorUpdateRate>
|
|
<infraredUpdateRate>1.0</infraredUpdateRate>
|
|
<depthTopicName>aligned_depth_to_color/image_raw</depthTopicName>
|
|
<depthCameraInfoTopicName>depth/camera_info</depthCameraInfoTopicName>
|
|
<colorTopicName>color/image_raw</colorTopicName>
|
|
<colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
|
|
<infrared1TopicName>infra1/image_raw</infrared1TopicName>
|
|
<infrared1CameraInfoTopicName>infra1/camera_info</infrared1CameraInfoTopicName>
|
|
<infrared2TopicName>infra2/image_raw</infrared2TopicName>
|
|
<infrared2CameraInfoTopicName>infra2/camera_info</infrared2CameraInfoTopicName>
|
|
<colorOpticalframeName>camera_color_optical_frame</colorOpticalframeName>
|
|
<depthOpticalframeName>camera_depth_optical_frame</depthOpticalframeName>
|
|
<infrared1OpticalframeName>camera_left_ir_optical_frame</infrared1OpticalframeName>
|
|
<infrared2OpticalframeName>camera_right_ir_optical_frame</infrared2OpticalframeName>
|
|
<rangeMinDepth>0.3</rangeMinDepth>
|
|
<rangeMaxDepth>3.0</rangeMaxDepth>
|
|
<pointCloud>true</pointCloud>
|
|
<pointCloudTopicName>depth/color/points</pointCloudTopicName>
|
|
<pointCloudCutoff>0.3</pointCloudCutoff>
|
|
</plugin>
|
|
</gazebo>
|
|
</xacro:macro>
|
|
|
|
</robot> |