-
Notifications
You must be signed in to change notification settings - Fork 558
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
Comments
Add manually a link to merge two sessionsFor 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 ~/.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: 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: 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): Generate local grids offlineFor the grid map generation, you can set You can also use $ rtabmap-reprocess --RGBD/CreateOccupancyGrid true --Grid/RayTracing true input.db output.db |
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. |
You're welcome! |
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.
The text was updated successfully, but these errors were encountered: