Re: Combine 3D Lidar and RGB-D Camera to create a single 3D point cloud (sensor fusion)
Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Combine-3D-Lidar-and-RGB-D-Camera-to-create-a-single-3D-point-cloud-sensor-fusion-tp10162p10175.html
Hi,
It seems that the rgbd_camera config in the URDF is wrong, or it is not compatible with the gazebo version I am using. To make the camera work correctly, I had to hard-code these values (based on that
example):
diff --git a/leo_description/urdf/macros.xacro b/leo_description/urdf/macros.xacro
index 98cdf40..b440345 100644
--- a/leo_description/urdf/macros.xacro
+++ b/leo_description/urdf/macros.xacro
@@ -750,11 +750,10 @@
<camera>
<image>
<format>R8G8B8</format>
- <width>${gazebo_camera_width}</width>
- <height>${gazebo_camera_height}</height>
+ <width>320</width>
+ <height>240</height>
</image>
- <horizontal_fov>${gazebo_camera_horizontal_fov}</horizontal_fov>
- <vertical_fov>${gazebo_camera_vertical_fov}</vertical_fov>
+ <horizontal_fov>1.047</horizontal_fov>
<clip>
<near>${gazebo_camera_color_clip_near}</near>
<far>${gazebo_camera_color_clip_far}</far>
It is because the cx/cy seem stuck at 160/120, which only work if resolution is 320/240. For the FOV, if I set something else, the cloud doesn't match anymore the lidar cloud.
Before

After

For rtabmap config using lidar and camera at the same time, here an updated version of your launch file
rtabmap_livox-rgbd_ML.py
cheers,
Mathieu