Kinect depth data is saturated to 1 meter
Hello everybody,
I'm using the simulated kinect of gazebo with the gazebo_ros_openni_kinect
plugin. It works fine when the kinect is looking at objects that are closer than 1 meter, but when the objects are at a distance bigger than 1 meter the depth value is always 1. It is not depending on the near/far clip set in the urdf of the kinect. I'm using ros groovy and gazebo 1.9, the image is taken from the topic /depth/image_raw
, but even rviz shows a semi-flat point cloud (that is, flat when the depth is bigger than 1 meter).
Does anyone know how to fix that problem? Thanks!
EDIT: the rgb image works correctly.
depth/image_raw:
https://www.dropbox.com/s/xlycy5troq7g4v0/depth.jpg
rgb/image_raw:
https://www.dropbox.com/s/y0am9uxv7ivub6b/rgb.jpg
This is how the kinect sensor is defined in the urdf:
<!-- xtion sensor -->
<gazebo reference="xtion_link">
<sensor type="depth" name="xtion_sensor">
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>3</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</camera>
<always_on>1</always_on>
<visualize>true</visualize>
<plugin name="Xtion_frame_controller" filename="libgazebo_ros_openni_kinect.so">
<alwaysOn>true</alwaysOn>
<updateRate>20.0</updateRate>
<cameraName>xtion</cameraName>
<imageTopicName>ir/image_raw</imageTopicName>
<cameraInfoTopicName>ir/camera_info</cameraInfoTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<frameName>xtion_depth_optical_frame</frameName>
<pointCloudCutoff>0.05</pointCloudCutoff>
<distortionK1>0.00000001</distortionK1>
<distortionK2>0.00000001</distortionK2>
<distortionK3>0.00000001</distortionK3>
<distortionT1>0.00000001</distortionT1>
<distortionT2>0.00000001</distortionT2>
</plugin>
</sensor>
</gazebo>
<!-- xtion rgb camera -->
<gazebo reference="xtion_link">
<sensor type="camera" name="xtion_rgb_camera">
<update_rate>20.0</update_rate>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>3</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</camera>
<always_on>1</always_on>
<visualize>true</visualize>
<plugin name="Xtion_rgb_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>20.0</updateRate>
<cameraName>xtion</cameraName>
<imageTopicName>rgb/image_raw</imageTopicName>
<cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
<frameName>xtion_rgb_optical_frame</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>