Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Multi session mapping for 3D LiDAR #689

Closed
robertsenputras opened this issue Dec 6, 2021 · 3 comments
Closed

Multi session mapping for 3D LiDAR #689

robertsenputras opened this issue Dec 6, 2021 · 3 comments

Comments

@robertsenputras
Copy link

robertsenputras commented Dec 6, 2021

Hi @matlabbe ,

I have searched for instructions regarding how to do multi-session mapping with only 3D lidar, and I seem didn't find the answer. For 3D LiDAR, is it possible to do multi-session mapping and stitch the db file together ? If so, could you share with me how to do it? I think a lot of people also need to know about this in the future. hehe.

*also I have another question about the gridmap. I saw from the last issue, the time for creating a gridmap is quite high. So I want to remove gridmap creation when creating 3d map and make a gridmap after the 3dmap is complete. Is there any option to make gridmap just at the end of the mapping process and also do raytracing?

Thank you.

@matlabbe
Copy link
Member

matlabbe commented Dec 10, 2021

Add manually a link to merge two sessions

For the first question, yes it is possible to create a multi-session database with only lidar. You have to manually link the session afterwards in rtabmap-databaseViewer (introlab/rtabmap#497). Here is an example using demo robot mapping bag played 2 times to create two disjoint sessions (visual loop closure detection disabled to simulate only lidar config):

$ roslaunch rtabmap_ros demo_robot_mapping.launch rtabmap_args:="-d --Kp/MaxFeatures -1"
$ rosbag play --clock demo_mapping.bag 
# Play till 110 seconds and kill all, then restart from 130 seconds 
# in the bag without clearing the previous session
$ roslaunch rtabmap_ros demo_robot_mapping.launch rtabmap_args:="--Kp/MaxFeatures -1"
$ rosbag play --clock -s 130 demo_mapping.bag
# Play till 85 seconds then kill all

Now you should have two disjoint maps where visually no loop closures can be found because the robot traversed the area in opposite directions. However, the lidar should see the same thing at some locations. Open the database in rtabmap-databaseViewer:

$ rtabmap-databaseViewer ~/.ros/rtabmap.db

In the Graph View, it will show one of the two maps, based on the root id parameter. You can switch session by setting a root id from another session. You can find the first node of each session by moving the main sliders until an image shows a label with "map0" or "map1". Here an example of switching the root id in Graph View:
Screenshot from 2021-12-10 09-23-07
Screenshot from 2021-12-10 09-23-21

To merge the session manually, select two nodes that should be seeing the same structures. Here we choose node 1 and 187 and click on Add button under Constraints View:
Screenshot from 2021-12-10 09-24-13
Press Yes for the first dialog. It will then show this one:
Screenshot from 2021-12-10 09-24-33
It tried to match the laser scans using Identity transform between them, but it is likely to fail as in reality the nodes have a rotation of about 80 deg between them. Press yes to enter manually the transform and set 80 deg for the yaw (uncheck Radian checkbox to set degrees):
Screenshot from 2021-12-10 09-42-15
Press Ok, you should then see in Constraints View the actual constraint between the node and in Graph View, you should see the two maps merged together.
Screenshot from 2021-12-10 09-42-28
Press Refine to better estimate the transform.
Screenshot from 2021-12-10 09-42-41
Our new constraint looks pretty accurate, but the two paths don't superpose perfectly, we need to add more constraints. Here an example to better align the bottom right corner (nodes 45 and 148):
Screenshot from 2021-12-10 09-36-59
When we hit Add, we would get again this error:
Screenshot from 2021-12-10 09-37-20
For this case, as the guess transform should be already quite close (as shown in the Constraints View), we will increase Icp/MaxTranslation to 0.3 to accept that constraint (open Core Parameters->Icp panel):
Screenshot from 2021-12-10 09-37-41
Click Add again, the constraint should be accepted and would appear in red in Graph View:
Screenshot from 2021-12-10 09-38-19

We could continue manually like that to add more and more constraints to better optimize the whole map, but we can also use Detect More Loop Closures tool to automatically add them. Open Gui Parameters View, go under Detect More Loop Closures panel and set those parameters (find loop closures in any orientation, force only loop closures between the sessions):
Screenshot from 2021-12-10 09-44-07
Click on Edit->"Detect more loop closures...", then the final results will look like this:
Screenshot from 2021-12-10 09-44-51

Generate local grids offline

For the grid map generation, you can set RGBD/CreateOccupancyGrid to false to avoid creating the local grids online. To recreate them afterwards with ray tracing, there is an option in rtabmap-databaseViewer (menu Edit->Regenerate all local grids...) to regenerate the local grids based on the parameters set in Core Parameters panel.
Screenshot from 2021-12-10 10-13-19

You can also use rtabmap-reprocess tool like this:

$ rtabmap-reprocess --RGBD/CreateOccupancyGrid true --Grid/RayTracing true input.db output.db

@robertsenputras
Copy link
Author

Thank you for your detailed explanation about the map stitching for multi-session mapping. I really appreciate your answer, It's very clear and detailed. It gives us, especially me a very deep understanding about your package. Glad to find your powerful package. Hope the others also find this explanation in the future.

Thanks a lot.

@matlabbe
Copy link
Member

You're welcome!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants