How to assemble point cloud from additional lidar (planar)

classic Classic list List threaded Threaded
6 messages Options
Reply | Threaded
Open this post in threaded view
|

How to assemble point cloud from additional lidar (planar)

alexr
Hi,

How do I incorporate an additional lidar that is vertically fixed wrt to the horizontal one. I have so far tested the laser_assembler package on a PR2 bag file and I am able to build point clouds from a tilting lidar (pr2 bag). For my current setup, I have a fixed horizontal lidar for ICP matching, an rgbd sensor for 3d mapping with IMU. So far RTABMAP works absolutely great with my setup. I would like to add an additional lidar (vertical fixed hokuyo) for getting point cloud and use the RTABMAP node to correct the map. Can you provide pointers as to how to accomplish  this setup using laser assembler node and rtabmap.

Thanks
Alex
------ Alex
Reply | Threaded
Open this post in threaded view
|

Re: How to assemble point cloud from additional lidar (planar)

matlabbe
Administrator
This post was updated on .
Hi Alex,

Look at this example. The downside is that rtabmap cannot subscribe to both 2D laser scan topic ("scan") and 3D point cloud topic ("scan_cloud") at the same time, so the horizontal lidar could not be saved in the map. To add scans from both lidars, the trick would be to merge the output point cloud of laser_assembler with the horizontal laser scan (which would need to be converted to a point cloud), then input the resulting merged point cloud to rtabmap node ("scan_cloud" topic).

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: How to assemble point cloud from additional lidar (planar)

alexr
Hi Mathieu,

I did not understand what you mean by the scan topic from the horizontal lidar cannot be used at the same time. From my understanding, the horizontal lidar in the RTABMAP lidar+rgbd camera+ odom is used to correct the scan matching and produce the grid map. Can't the vertical lidar along with the rgbd camera can be used to make more dense point cloud. The vertical lidar scan topic can be properly remapped to merge with scan_cloud. Can you elaborate whether this is possible or I am wrong? I have so far managed to test the laser_assembler node on gazebo and it works fine. Haven't combined it yet with SLAM for correcting the point cloud map.

Thanks
Alex
------ Alex
Reply | Threaded
Open this post in threaded view
|

Re: How to assemble point cloud from additional lidar (planar)

matlabbe
Administrator
rtabmap subscribes either to a LaserScan topic ("scan") or a PointCloud2 topic ("scan_cloud"), not both at the same time. You would have PointCloud2 + RGBDCamera + odom to produce the map. The PointCloud2 input would include both the horizontal and vertical scans.

horizontal lidar (/base_scan) --> scan_to_cloud (/base_scan_cloud) --
                                                                     \
                                                                      merge_clouds (/scan_cloud) ----
                                                                     /                               \
vertical lidar (/v_scan)--> laser_assembler (/assembled_scans) ------                                 \
                            /                                                                          \
                           / (tf odom)                                                                  \
                          /                                                                              \
tf -------------------------------------------------------------------------------------------------\     \
                                                                                                     \     \
Odom (/odom)----------------------------------------------------------------------------------------> rtabmap
                                                                                                      /
RGBD images (camera/rgb/image_rect_color, camera/depth_registered/image_raw, camera/rgb/camera_info)--

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: How to assemble point cloud from additional lidar (planar)

alexr
Dear Mathieu,

Ok i got the point. I do not have the setup ready. I will report back once I finish testing this setup. Can you tell me if tilting the lidar will make any difference?  

Thank you for the pointers.

Alex
------ Alex
Reply | Threaded
Open this post in threaded view
|

Re: How to assemble point cloud from additional lidar (planar)

matlabbe
Administrator
If you tilt the lidar just make sure TF/urdf is also updated.