3D LiDAR + Odometry + RGB Image for Loop Closure

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

3D LiDAR + Odometry + RGB Image for Loop Closure

loopclosure0
Hello,

I am trying to create a 3D map, with a 2D costmap, then save that .db and load it later for localization. My approach right now is to use a 3D LiDAR for mapping, and rgb images for relocalization and loop closure once I've put rtabmap into localization mode.

As of right now, I'm able to create the 3D map and 2D Costmap with a 3D LiDAR, and rgb images, and my overall map looks great. However, when I open the map in localization mode, despite the fact that I'm able to bring up all of the relevant information in rtabmap after downloading the .db, I'm not ever able to complete loop closure properly or relocalize to the correct point in the map. This means that my odometry basically just drifts, and never actually aligns with the costmap, which means that I'm not really localizing in the costmap. I can see the attempted loop closures in the GUI, and they have hundreds of good matches, and the odometry is approximately in the correct position, but everytime my loop closure is rejected, giving a message similar to the one below:  

[ WARN] (2019-08-27 11:54:12.135) Rtabmap.cpp:2151::process() Rejected loop closure 11 -> 464: Not enough inliers 0/20 (matches=547) between 11 and 464

I'd like these loop closures to be accepted, but I'm not sure how to increase the number of inliers.

I'm not sure why there are no inliers found, despite the fact that I'm finding hundreds of matches that look pretty good to me. Do I simply need to relax my parameters some? I'm using Odom/Strategy = 1, I've tried changing various parameters in /Vis/, but haven't been able to increase the number of inliers higher than 0. I think it's possible there are parameters I need to relax in order to get more inliers, but I'm not sure which parameters. Is there something I'm doing wrong? My launch file is attached, which I used for both mapping and localization (just setting localization:=true for localization mode).

3D_lidar_and_rgb_images_mapping_and_localization.launch 

Reply | Threaded
Open this post in threaded view
|

Re: 3D LiDAR + Odometry + RGB Image for Loop Closure

matlabbe
Administrator
This post was updated on .
As you are using a ZED camera, I suggest that you feed the ZED depth image to rtabmap as well. Use rgbd_sync  to pre-sync zed topics and set subscribe_rgbd=true for rtabmap and rtabmap_viz nodes (like in this configuration). The reason that loop closures are rejected is that features are poorly triangulated using only RGB image without depth information. To have good triangulation with that kind of setup, we would have to increase Rtabmap/DetectionRate and make sure the odometry received represents accurately the camera motion. Another option is if the field of view of the RGB camera and lidar intersects (in case you want to move from ZED camera to a single RGB camera), we could create a depth image for the RGB camera using the lidar point cloud (see this post) with pointcloud_to_depthimage node.
Reply | Threaded
Open this post in threaded view
|

Re: 3D LiDAR + Odometry + RGB Image for Loop Closure

loopclosure0
Thanks for your help!

I've tried using a ZED Stereo Camera at the same time as the 3D LiDAR, and it is very slow, so I figured I could do loop closure with just the RGB camera. It makes sense that the camera needs depth information though. Another reason I'd rather not use the ZED Stereo camera is because it's pointcloud data is significantly worse than the data from the 3D LiDAR. Is there any way to use the ZED Stereo camera for loop closure only, and ignore the pointcloud (not add it to the map)?
Reply | Threaded
Open this post in threaded view
|

Re: 3D LiDAR + Odometry + RGB Image for Loop Closure

matlabbe
Administrator
Hi,

Yes, you can choose lidar for the 3D occupancy grid. Just set parameter Grid/FromDepth to false. /rtabmap/cloud_map will be generated from the lidar.

cheers,
Mathieu