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

Feature request: Modify grid_map #213

Closed
paulsammut opened this issue Dec 13, 2017 · 28 comments
Closed

Feature request: Modify grid_map #213

paulsammut opened this issue Dec 13, 2017 · 28 comments

Comments

@paulsammut
Copy link

paulsammut commented Dec 13, 2017

Hello! I am creating good maps with rtabmap, and am using the grid_map output for planning use. My currently workflow is I first do a mapping run with settings that are good for mapping, then I save the database and run the refinements and more loop closures in rtabmap-database viewer. I then use the database in just localization mode for normal operation of my robot. My question is: Can I modify the grid_map published by rtab?

It would be nice to add in some things into the 2d occupancy map that rtabmap serves up. For example, i'd like to create "lanes" for my robot to travel in, to make it easier for path planning with multiple waypoints. Like this:
map

Is there an easy way to do this? I was also thinking of maybe creating a separate map that has my stuff on it, and serve it with ros' map server and publish a static tf link to the rtabmap map frame.

Thanks for all your work!

@matlabbe
Copy link
Member

Hi,

The short answer: use the map_server workaround you described as we cannot modify the grid map in the database.

The long answer: RTAB-Map doesn't keep the global occupancy grid map saved like this in the database, it keeps all local occupancy grid maps created for each node in the map, then reconstruct the global map on runtime. It is because on loop closure detection, the graph may change so that global map must be reconstructed. In localization mode, the map would be static as there are no map corrections, so the map could be saved as is in the database. However, it is not always the case because of the memory management (when used) that could transfer/retrieve some parts of the map even in localization mode, so that graph optimization should be done again.

Well, for the special case of localization without memory management, we could think about saving the global map in database for convenience, instead of manually using the map_saver/map_server approach, to keep all data at the same place. That feature would require at least an export/import approach to get the occupancy grid map in an image editor, then re-save it back to database. The Admin table could be used to save the last optimized occupancy grid with corresponding optimized graph (similar to what is done for the optimized mesh saved by RTAB-Map Tango).

If we address the lane preference, how would you edit the map to tell the planner that some cells should be used over others? Currently the cells are 0=empty, -1=unknown and 100=obstacle. While not used by rtabmap, values between 0 and 100 are probabilities of an obstacle, probably using values 101 to 128 and -2 to -128 may encode the lane preferences. Another approach to set lane preference, without the grid map, is to encode the preferences in the nodes of the graph (using label field for example). I already used this on a robot where I had to set zones where the robot could move faster or slower. The topic /rtabmap/mapGraph contains poses of the map with their label, so it is possible to know indirectly the position of the lanes (paths that you drove the robot during the mapping phase).

cheers,
Mathieu

@paulsammut
Copy link
Author

paulsammut commented Dec 15, 2017

Thanks, I dug through the db hoping to find the grid, but couldn't as per your explanation :).
I intend to use a static layer 2d costmap, and I will be able to set the values of the lanes accordingly. For instance, "suggested" lanes can have a lower cost value, allowing the robot to enter or exit the area if need be, and stuff like bike lanes where I want my robot to stay in can have a higher costs.

I think trying to modify the map rtabmap serves is not the right way to go as that would be stretching its intended purpose. I'll see how well it would be to integrate the map_saver/map_server approach.

It seems there there is a philosophical approach to make rtabmap more of a "live mapper" type system, that maps and handles loop closures while normal robot operation, instead of a dedicate map maker and dedicated map localizer/server. I don't see how this works because if you intend to map while operating, you cannot operate in an environment with dynamic obstacles. As an added bonus, separating those tasks gives you the benefit of allocating precious CPU cycles to the task at hand.

@matlabbe
Copy link
Member

matlabbe commented Dec 15, 2017

Current research using rtabmap is about long-term continuous SLAM(see this paper for example): always updating the map while operating, so that the map can adapt to changes in environment and extend during exploration. Indeed, for many practical applications, it is simpler to go through a mapping phase, then switch to a localization phase. Being able to save the global grid map in the database as explained in my previous post would help then help to do this kind of application more easily and efficiently.

Cheers,
Mathieu

@paulsammut
Copy link
Author

paulsammut commented Dec 15, 2017

Cool, if you did that, I'd also be able to go into the grid map and modify it to take out false obstacle cells where people walked in the front of the robot :)

@paulsammut
Copy link
Author

paulsammut commented Mar 1, 2018

I've been working on this more and I have run into an issue with the map that rtab publishes changing over time.

My approach is as follows:

  • Create a map of the environment with rtabmap
  • Download the map using map_server
  • Edit the map .pgm file, clean up the ghost obstacles and add things like lanes with variable cost
  • Run move_base with the global map having one static 2d costmap layer that is seeded by map_server, that serves my edited map
  • Run rtabmap in localization mode so it can publish the /map to /odom transform

This works but only for a few seconds. After that, rtabmap seems to serve a map that is slightly shifted or rotated. It seems like rtabmap isn't just sending a new transform, but modifying the map itself and shifting it to fit the transform. Any advice? Is there maybe a setting I could change that would leave rtab's served map unchanged?

Here is a shot of me running rtabmap in localization mode, while serving up my custom map. I am also displaying the /grid_map publishes by rtabmap, which is localized properly, but shifts causing a discrepancy with the custom map i and using in move_base. The rtabmap /grid_map is colored in as a map and the custom map is colored in as a costmap.

lanes_shifting

Thanks!
-Paul

@matlabbe
Copy link
Member

matlabbe commented Mar 1, 2018

If /map -> /odom stays at Identity transform and the map rotates/translates on localization, it looks like that RGBD/OptimizeFromGraphEnd parameter is set to true, is it?

@paulsammut
Copy link
Author

paulsammut commented Mar 3, 2018

That did it!!! Thanks man! I'll do a quick writeup about how I used this solution and post it up here.

matlabbe added a commit to introlab/rtabmap that referenced this issue Apr 4, 2018
…introlab/rtabmap_ros#220). Parameters: fixed Icp default parameters when not built with libpointmatcher, added RGBD/SavedLocalizationIgnored (default false). DbViewer: added Export/Import 2D map (introlab/rtabmap_ros#213).
matlabbe added a commit that referenced this issue Apr 4, 2018
…default on localization, rtabmap will adjust the odometry to match the latest saved localization in the database (starting automatically from where the robot shut down, #220).
@matlabbe
Copy link
Member

matlabbe commented Apr 4, 2018

Using commits above, the grid map is automatically saved to database on exit. We can use DatabaseViewer -> File- > Export saved 2D map... to export the map in pgm image file. That file can be edited using a image editor to remove/add obstacles. Then with File -> Import 2D map, the map can be re-imported and overwriting the one saved in the database. When relaunching the robot in localization mode, the edited map will be used.

@paulsammut
Copy link
Author

Hey @matlabbe thanks for the update! I just pulled the latest master commits for both rtabmap and rtabmap_ros and gave this a go. I did it using my sim gazebo setup and found that rtabmap was freezing after about a couple of minutes of mapping. By freezing i mean that new nodes were being added and rtabmapviz shoes no new information. I reverted back to the old version I was using and problem went away. Didn't have enough time to dig into it, just wanted to let you know.

-Paul

@matlabbe
Copy link
Member

Thx to let me know, I am however not able to reproduce the problem when wandering a couple of minutes with turtlebot gazebo demo. A freezing without any errors may be related with some input topics not published anymore or that they are badly synchronized (some topics are lagging for example). If it is the GUI which is not responsive, maybe a GPU related problem.

Well, if you retry the latest version, get screenshot and the terminal log status.

cheers,
Mathieu

@tugbakara
Copy link

Using commits above, the grid map is automatically saved to database on exit. We can use DatabaseViewer -> File- > Export saved 2D map... to export the map in pgm image file. That file can be edited using a image editor to remove/add obstacles. Then with File -> Import 2D map, the map can be re-imported and overwriting the one saved in the database. When relaunching the robot in localization mode, the edited map will be used.

Is there any other solution for ros side only?

@matlabbe
Copy link
Member

The database should be closed before editing the map, so not sure how we could do that with ROS. Note that the grid map can be edited directly in rtabmap-databaseViewer without having to export/import back the map. See http://official-rtab-map-forum.206.s1.nabble.com/post-processing-manually-add-obstacles-to-map-tp6985p6993.html

@tugbakara
Copy link

tugbakara commented Oct 19, 2022

Thanks @matlabbe , we solved it from databaseviewer but we are facing one issue that is except octomap_grid topic others are recreates the map even if we open in localization mode that's why we re trying to import modified octomap_grid map but there is not anything about it , databaseviewer only takes grid_map but in this map our obstacles are very rare compared to octomap_grid. Is there any solution to import changed octomap_grid map, or to stop mapping while opening grid_map with localization?

@matlabbe
Copy link
Member

We would need to add an option in DatabaseViewer to select which map to edit and save. As a workaround, you could use rosrun map_server map_saver map=/rtabmap/octomap_grid with the octomap_grid topic, this will save a PGM of the octomap grid. You can then try to edit/import that PGM using DatabaseViewer as the new optimized grid map.

@tugbakara
Copy link

tugbakara commented Oct 20, 2022

I will try it but do you have an idea about when I open the map for localization with rtabmap/grid_map topic or others (except octomap_grid) it starts to create map again on existing map, how can I stop it ?

@matlabbe
Copy link
Member

It feels you are not really in localization mode. Mem/IncrementalMemory parameter should be false, otherwise rtabmap will start a new session and re-create the grid. Can you share the database?

@tugbakara
Copy link

tugbakara commented Oct 21, 2022

I already set the param false, I will send the db when I am available.
Here is my db

@tugbakara
Copy link

tugbakara commented Oct 22, 2022

You can then try to edit/import that PGM using DatabaseViewer as the new optimized grid map.

It didn't work.

@matlabbe
Copy link
Member

for some reason, the database doesn't have RGBD/CreateOccupancyGrid set to true. Fix it like this:

rtabmap-reprocess --RGBD/CreateOccupancyGrid true ofisstatic.db output.db

Then doing:

roscore
rosrun rtabmap_ros rtabmap _database_path:=~/Downloads/output.db
rosrun map_server map_saver map:=/octomap_grid
rosservice call /publish_map 0 1 0

we can get the octomap grid pgm file. However, unfortunately, I was wrong, we cannot import it back in databaseViewer because of this error:
Screenshot from 2022-10-23 11-30-40

I updated databaseViewer to add an option to regenerate optimized map from OctoMap. Here the new steps (from output.db above):

rtabmap-databaseViewer ~/Downloads/output.db
  • View->"Graph view"
  • File->"Regenerate optimized 2d map..."
  • At this point, the grid created from OctoMap will be saved in the database. You can preview it with File->"View optimized 2d map..."

Then on ROS, to verify that the same map is used under grid_map topic:

roscore
rosrun rtabmap_ros rtabmap _database_path:=~/Downloads/output.db
rviz
rosservice call /publish_map 0 1 0

Screenshot from 2022-10-23 12-13-39

@tugbakara
Copy link

rtabmap-reprocess --RGBD/CreateOccupancyGrid true ofisstatic.db output.db

when I run this command I got some erros like:
Custom parameters: RGBD/CreateOccupancyGrid = true Set working directory to ".". Target database version: "0.20.21" (set explicitly --Db/TargetVersion "" to output with latest version. Reprocessing data of "ofisstatic.db"... High variance detected, triggering a new map... Processed 1/161 nodes [id=1 map=0 opt_graph=1]... 193ms Processed 2/161 nodes [id=2 map=0 opt_graph=2]... 71ms Processed 3/161 nodes [id=3 map=0 opt_graph=3]... 49ms Processed 4/161 nodes [id=4 map=0 opt_graph=4]... 48ms Processed 5/161 nodes [id=5 map=0 opt_graph=5]... 51ms Processed 6/161 nodes [id=6 map=0 opt_graph=6]... 46ms Processed 7/161 nodes [id=7 map=0 opt_graph=7]... 48ms Processed 8/161 nodes [id=8 map=0 opt_graph=8]... 50ms Processed 9/161 nodes [id=9 map=0 opt_graph=9]... 48ms Processed 10/161 nodes [id=10 map=0 opt_graph=10]... 46ms [ERROR] (2022-10-24 11:07:06.961) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 11/161 nodes [id=11 map=0 opt_graph=11]... 99ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:07.051) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 12/161 nodes [id=12 map=0 opt_graph=12]... 83ms Prox on 2 [0] [ERROR] (2022-10-24 11:07:07.148) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 13/161 nodes [id=13 map=0 opt_graph=13]... 81ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:07.247) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 14/161 nodes [id=14 map=0 opt_graph=14]... 92ms Prox on 2 [0] [ERROR] (2022-10-24 11:07:07.349) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 15/161 nodes [id=15 map=0 opt_graph=15]... 84ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:07.450) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 16/161 nodes [id=16 map=0 opt_graph=16]... 86ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:07.553) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 17/161 nodes [id=17 map=0 opt_graph=17]... 87ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:07.656) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 18/161 nodes [id=18 map=0 opt_graph=18]... 80ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:07.748) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 19/161 nodes [id=19 map=0 opt_graph=19]... 84ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:07.849) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 20/161 nodes [id=20 map=0 opt_graph=20]... 86ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:07.950) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 21/161 nodes [id=21 map=0 opt_graph=21]... 74ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:08.038) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 22/161 nodes [id=22 map=0 opt_graph=22]... 87ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:08.137) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 23/161 nodes [id=23 map=0 opt_graph=23]... 89ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:08.240) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 24/161 nodes [id=24 map=0 opt_graph=24]... 73ms Prox on 1 [0] [ERROR] (2022-10-24 11:07:08.338) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 25/161 nodes [id=25 map=0 opt_graph=25]... 99ms Prox on 2 [0] [ERROR] (2022-10-24 11:07:08.442) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 26/161 nodes [id=26 map=0 opt_graph=26]... 75ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:08.536) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 27/161 nodes [id=27 map=0 opt_graph=27]... 93ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:08.639) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 28/161 nodes [id=28 map=0 opt_graph=28]... 89ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:08.743) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 29/161 nodes [id=29 map=0 opt_graph=29]... 78ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:08.839) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 30/161 nodes [id=30 map=0 opt_graph=30]... 93ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:08.940) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 31/161 nodes [id=31 map=0 opt_graph=31]... 78ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:09.035) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 32/161 nodes [id=32 map=0 opt_graph=32]... 87ms Prox on 22 [0] [ERROR] (2022-10-24 11:07:09.136) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 33/161 nodes [id=33 map=0 opt_graph=33]... 75ms Prox on 22 [0] [ERROR] (2022-10-24 11:07:09.224) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 34/161 nodes [id=34 map=0 opt_graph=34]... 90ms Prox on 22 [0] [ERROR] (2022-10-24 11:07:09.331) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 35/161 nodes [id=35 map=0 opt_graph=35]... 87ms Prox on 25 [0] [ERROR] (2022-10-24 11:07:09.436) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 36/161 nodes [id=36 map=0 opt_graph=36]... 92ms Prox on 3 [0] [ERROR] (2022-10-24 11:07:09.544) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 37/161 nodes [id=37 map=0 opt_graph=37]... 94ms Prox on 24 [0] [ERROR] (2022-10-24 11:07:09.648) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 38/161 nodes [id=38 map=0 opt_graph=38]... 93ms Prox on 22 [0] [ERROR] (2022-10-24 11:07:09.758) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 39/161 nodes [id=39 map=0 opt_graph=39]... 96ms Prox on 19 [0] [ERROR] (2022-10-24 11:07:09.866) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 40/161 nodes [id=40 map=0 opt_graph=40]... 94ms Prox on 20 [0] [ERROR] (2022-10-24 11:07:09.977) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 41/161 nodes [id=41 map=0 opt_graph=41]... 96ms Prox on 19 [0] [ERROR] (2022-10-24 11:07:10.082) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 42/161 nodes [id=42 map=0 opt_graph=42]... 92ms Prox on 19 [0] [ERROR] (2022-10-24 11:07:10.190) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 43/161 nodes [id=43 map=0 opt_graph=43]... 93ms Prox on 17 [0] [ERROR] (2022-10-24 11:07:10.296) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 44/161 nodes [id=44 map=0 opt_graph=44]... 80ms Prox on 20 [0] [ERROR] (2022-10-24 11:07:10.390) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 45/161 nodes [id=45 map=0 opt_graph=45]... 90ms Prox on 25 [0] [ERROR] (2022-10-24 11:07:10.493) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 46/161 nodes [id=46 map=0 opt_graph=46]... 88ms Prox on 34 [0] [ERROR] (2022-10-24 11:07:10.596) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 47/161 nodes [id=47 map=0 opt_graph=47]... 89ms Prox on 32 [0] [ERROR] (2022-10-24 11:07:10.700) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 48/161 nodes [id=48 map=0 opt_graph=48]... 88ms Prox on 38 [0] [ERROR] (2022-10-24 11:07:10.802) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 49/161 nodes [id=49 map=0 opt_graph=49]... 83ms Prox on 39 [0] [ERROR] (2022-10-24 11:07:10.900) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 50/161 nodes [id=50 map=0 opt_graph=50]... 94ms Prox on 19 [0] [ERROR] (2022-10-24 11:07:11.011) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 51/161 nodes [id=51 map=0 opt_graph=51]... 96ms Prox on 38 [0] [ERROR] (2022-10-24 11:07:11.117) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 52/161 nodes [id=52 map=0 opt_graph=52]... 92ms Prox on 40 [0] [ERROR] (2022-10-24 11:07:11.226) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 53/161 nodes [id=53 map=0 opt_graph=53]... 88ms Prox on 40 [0] [ERROR] (2022-10-24 11:07:11.327) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 54/161 nodes [id=54 map=0 opt_graph=54]... 92ms Prox on 40 [0] [ERROR] (2022-10-24 11:07:11.437) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 55/161 nodes [id=55 map=0 opt_graph=55]... 88ms Prox on 41 [0] [ERROR] (2022-10-24 11:07:11.536) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 56/161 nodes [id=56 map=0 opt_graph=56]... 79ms Prox on 17 [0] [ERROR] (2022-10-24 11:07:11.631) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 57/161 nodes [id=57 map=0 opt_graph=57]... 95ms Prox on 18 [0] [ERROR] (2022-10-24 11:07:11.741) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 58/161 nodes [id=58 map=0 opt_graph=58]... 95ms Prox on 17 [0] [ERROR] (2022-10-24 11:07:11.850) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 59/161 nodes [id=59 map=0 opt_graph=59]... 95ms Prox on 18 [0] [ERROR] (2022-10-24 11:07:11.959) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 60/161 nodes [id=60 map=0 opt_graph=60]... 95ms Prox on 19 [0] [ERROR] (2022-10-24 11:07:12.070) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 61/161 nodes [id=61 map=0 opt_graph=61]... 92ms Prox on 19 [0] Processed 62/161 nodes [id=62 map=0 opt_graph=62]... 1397ms Prox on 34 [0] Processed 63/161 nodes [id=63 map=0 opt_graph=63]... 1233ms Processed 64/161 nodes [id=64 map=0 opt_graph=64]... 1119ms Processed 65/161 nodes [id=65 map=0 opt_graph=65]... 1082ms Processed 66/161 nodes [id=66 map=0 opt_graph=66]... 1058ms Processed 67/161 nodes [id=67 map=0 opt_graph=67]... 1025ms Processed 68/161 nodes [id=68 map=0 opt_graph=68]... 66ms Processed 69/161 nodes [id=69 map=0 opt_graph=69]... 70ms Processed 70/161 nodes [id=70 map=0 opt_graph=70]... 1017ms Processed 71/161 nodes [id=71 map=0 opt_graph=71]... 94ms Processed 72/161 nodes [id=72 map=0 opt_graph=72]... 114ms Processed 73/161 nodes [id=73 map=0 opt_graph=73]... 118ms Processed 74/161 nodes [id=74 map=0 opt_graph=74]... 123ms Processed 75/161 nodes [id=75 map=0 opt_graph=75]... 110ms Processed 76/161 nodes [id=76 map=0 opt_graph=76]... 111ms Processed 77/161 nodes [id=77 map=0 opt_graph=77]... 1018ms Processed 78/161 nodes [id=78 map=0 opt_graph=78]... 1027ms Processed 79/161 nodes [id=79 map=0 opt_graph=79]... 110ms Prox on 3 [0] Processed 80/161 nodes [id=80 map=0 opt_graph=80]... 116ms Processed 81/161 nodes [id=81 map=0 opt_graph=81]... 125ms Prox on 71 [0] Processed 82/161 nodes [id=82 map=0 opt_graph=82]... 93ms Processed 83/161 nodes [id=83 map=0 opt_graph=83]... 105ms Processed 84/161 nodes [id=84 map=0 opt_graph=84]... 1036ms Processed 85/161 nodes [id=85 map=0 opt_graph=85]... 998ms Prox on 75 [0] Processed 86/161 nodes [id=86 map=0 opt_graph=86]... 1034ms Prox on 73 [0] Processed 87/161 nodes [id=87 map=0 opt_graph=87]... 1037ms Prox on 72 [0] Processed 88/161 nodes [id=88 map=0 opt_graph=88]... 1055ms Prox on 71 [0] Processed 89/161 nodes [id=89 map=0 opt_graph=89]... 111ms Prox on 71 [0] Processed 90/161 nodes [id=90 map=0 opt_graph=90]... 142ms Prox on 72 [0] Processed 91/161 nodes [id=91 map=0 opt_graph=91]... 168ms Prox on 72 [0] Processed 92/161 nodes [id=92 map=0 opt_graph=92]... 1026ms Prox on 73 [0] Processed 93/161 nodes [id=93 map=0 opt_graph=93]... 1007ms Prox on 73 [0] [ERROR] (2022-10-24 11:07:31.465) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:31.509) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 94/161 nodes [id=94 map=0 opt_graph=94]... 111ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:31.606) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:31.680) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 95/161 nodes [id=95 map=0 opt_graph=95]... 158ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:31.777) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:31.830) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 96/161 nodes [id=96 map=0 opt_graph=96]... 136ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:31.923) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:31.985) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 97/161 nodes [id=97 map=0 opt_graph=97]... 135ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:32.080) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:32.142) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 98/161 nodes [id=98 map=0 opt_graph=98]... 142ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:32.236) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:32.302) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 99/161 nodes [id=99 map=0 opt_graph=99]... 146ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:32.396) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:32.470) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 100/161 nodes [id=100 map=0 opt_graph=100]... 152ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:32.567) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:32.628) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 101/161 nodes [id=101 map=0 opt_graph=101]... 145ms Prox on 74 [0] [ERROR] (2022-10-24 11:07:32.737) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:32.799) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 102/161 nodes [id=102 map=0 opt_graph=102]... 155ms Prox on 73 [0] [ERROR] (2022-10-24 11:07:32.904) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:32.986) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 103/161 nodes [id=103 map=0 opt_graph=103]... 171ms Prox on 73 [0] [ERROR] (2022-10-24 11:07:33.071) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:33.124) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 104/161 nodes [id=104 map=0 opt_graph=104]... 125ms Prox on 93 [0] Processed 105/161 nodes [id=105 map=0 opt_graph=105]... 1015ms Prox on 94 [0] [ERROR] (2022-10-24 11:07:34.238) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:34.305) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 106/161 nodes [id=106 map=0 opt_graph=106]... 139ms Prox on 75 [0] [ERROR] (2022-10-24 11:07:34.387) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:34.456) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 107/161 nodes [id=107 map=0 opt_graph=107]... 136ms Prox on 80 [0] [ERROR] (2022-10-24 11:07:34.553) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:34.622) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 108/161 nodes [id=108 map=0 opt_graph=108]... 150ms Prox on 82 [0] [ERROR] (2022-10-24 11:07:34.715) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:34.783) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 109/161 nodes [id=109 map=0 opt_graph=109]... 145ms Prox on 84 [0] [ERROR] (2022-10-24 11:07:34.865) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:34.934) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 110/161 nodes [id=110 map=0 opt_graph=110]... 137ms Prox on 85 [0] [ERROR] (2022-10-24 11:07:35.020) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:35.088) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 111/161 nodes [id=111 map=0 opt_graph=111]... 142ms Prox on 86 [0] [ERROR] (2022-10-24 11:07:35.177) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:35.241) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 112/161 nodes [id=112 map=0 opt_graph=112]... 139ms Prox on 86 [0] [ERROR] (2022-10-24 11:07:35.330) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:35.380) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 113/161 nodes [id=113 map=0 opt_graph=113]... 125ms Prox on 87 [0] [ERROR] (2022-10-24 11:07:35.472) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:35.538) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 114/161 nodes [id=114 map=0 opt_graph=114]... 140ms [ERROR] (2022-10-24 11:07:35.661) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 115/161 nodes [id=115 map=0 opt_graph=115]... 110ms [ERROR] (2022-10-24 11:07:35.809) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 116/161 nodes [id=116 map=0 opt_graph=116]... 134ms Prox on 62 [0] Processed 117/161 nodes [id=117 map=0 opt_graph=117]... 126ms Prox on 62 [0] Processed 118/161 nodes [id=118 map=0 opt_graph=118]... 126ms Prox on 62 [0] Processed 119/161 nodes [id=119 map=0 opt_graph=119]... 119ms Processed 120/161 nodes [id=120 map=0 opt_graph=120]... 116ms Processed 121/161 nodes [id=121 map=0 opt_graph=121]... 104ms Processed 122/161 nodes [id=122 map=0 opt_graph=122]... 116ms Processed 123/161 nodes [id=123 map=0 opt_graph=123]... 118ms Prox on 34 [0] Processed 124/161 nodes [id=124 map=0 opt_graph=124]... 117ms Prox on 114 [0] Processed 125/161 nodes [id=125 map=0 opt_graph=125]... 112ms Prox on 115 [0] Processed 126/161 nodes [id=126 map=0 opt_graph=126]... 111ms Processed 127/161 nodes [id=127 map=0 opt_graph=127]... 111ms Processed 128/161 nodes [id=128 map=0 opt_graph=128]... 105ms Processed 129/161 nodes [id=129 map=0 opt_graph=129]... 82ms Prox on 119 [0] Processed 130/161 nodes [id=130 map=0 opt_graph=130]... 163ms Processed 131/161 nodes [id=131 map=0 opt_graph=131]... 100ms Processed 132/161 nodes [id=132 map=0 opt_graph=132]... 100ms Processed 133/161 nodes [id=133 map=0 opt_graph=133]... 100ms Prox on 123 [0] Processed 134/161 nodes [id=134 map=0 opt_graph=134]... 92ms Processed 135/161 nodes [id=135 map=0 opt_graph=135]... 90ms Processed 136/161 nodes [id=136 map=0 opt_graph=136]... 98ms Processed 137/161 nodes [id=137 map=0 opt_graph=137]... 107ms Processed 138/161 nodes [id=138 map=0 opt_graph=138]... 1062ms Processed 139/161 nodes [id=139 map=0 opt_graph=139]... 1044ms Processed 140/161 nodes [id=140 map=0 opt_graph=140]... 1012ms Processed 141/161 nodes [id=141 map=0 opt_graph=141]... 123ms Prox on 131 [0] Processed 142/161 nodes [id=142 map=0 opt_graph=142]... 142ms Prox on 132 [0] Processed 143/161 nodes [id=143 map=0 opt_graph=143]... 98ms Processed 144/161 nodes [id=144 map=0 opt_graph=144]... 1033ms Prox on 134 [0] [ERROR] (2022-10-24 11:07:43.057) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 145/161 nodes [id=145 map=0 opt_graph=145]... 99ms Prox on 135 [0] [ERROR] (2022-10-24 11:07:43.186) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 146/161 nodes [id=146 map=0 opt_graph=146]... 119ms Prox on 133 [0] Processed 147/161 nodes [id=147 map=0 opt_graph=147]... 1019ms Prox on 132 [0] Processed 148/161 nodes [id=148 map=0 opt_graph=148]... 1018ms Prox on 131 [0] Processed 149/161 nodes [id=149 map=0 opt_graph=149]... 1013ms Prox on 130 [0] [ERROR] (2022-10-24 11:07:46.378) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 150/161 nodes [id=150 map=0 opt_graph=150]... 110ms Prox on 129 [0] [ERROR] (2022-10-24 11:07:46.495) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 151/161 nodes [id=151 map=0 opt_graph=151]... 105ms Prox on 128 [0] [ERROR] (2022-10-24 11:07:46.619) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 152/161 nodes [id=152 map=0 opt_graph=152]... 112ms Prox on 127 [0] [ERROR] (2022-10-24 11:07:46.749) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 153/161 nodes [id=153 map=0 opt_graph=153]... 120ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:46.863) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 154/161 nodes [id=154 map=0 opt_graph=154]... 101ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:46.993) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 155/161 nodes [id=155 map=0 opt_graph=155]... 121ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:47.134) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 156/161 nodes [id=156 map=0 opt_graph=156]... 122ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:47.260) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 157/161 nodes [id=157 map=0 opt_graph=157]... 116ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:47.399) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 158/161 nodes [id=158 map=0 opt_graph=158]... 126ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:47.526) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 159/161 nodes [id=159 map=0 opt_graph=159]... 117ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:47.612) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:47.681) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 160/161 nodes [id=160 map=0 opt_graph=160]... 141ms Prox on 126 [0] [ERROR] (2022-10-24 11:07:47.755) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. [ERROR] (2022-10-24 11:07:47.814) Optimizer.cpp:446::optimizeBA() Optimizer 0 doesn't implement optimizeBA() method. Processed 161/161 nodes [id=161 map=0 opt_graph=161]... 120ms Prox on 126 [0] Total loop closures = 111 (Loop=0, Prox=111, In Motion=111/161) Closing database "output.db"... Closing database "output.db"... done!

If it will any other things happen, I will write them here.

@matlabbe
Copy link
Member

The computer you are reprocessing the database doesn't have rtabmap with g2o dependency. TORO optimizer is used as backup but it doesn't support BA optimization.

@tugbakara
Copy link

Thanks @matlabbe !

@dimitryn
Copy link

dimitryn commented Dec 7, 2022

Hi @matlabbe , can you please summarize steps to modify grid_map. thank you .
I an using latest rtabmap-databaseviewer tool to add obstacle .
I did all steps from File->Open database ... File->Import optimized 2d map .
Next steps are not clear for me , If I run "Renerate optimized 2d map" should see change in "Graph view" or "Occupacy grip" ?
How imported pgm image change db ?
Thanks.

@matlabbe
Copy link
Member

You won't see the changes in Graph View, you can make sure your changes are there by doing File->Edit optimized 2d map..., then you will see the actual optimized/modified occupancy grid that rtabmap will use when relaunching in localization mode. See also http://official-rtab-map-forum.206.s1.nabble.com/post-processing-manually-add-obstacles-to-map-tp6985p6993.html:
image

@dimitryn
Copy link

Hi @matlabbe thanks for reply
1.My steps. Open database -> Export optimized 2d map -> edit image ->Import optimized 2d map -> Close optimized 2d map.
2.No dbDriver_->save2DMap called on closed (I set breakpoint on close). When I reopen databse and call ->Edit optimzed 2d map , it show 2d image without obstacle !
3.Should regenerate 2d map be called on some step ?
thanks

@matlabbe
Copy link
Member

Can you try editing the map with the embedded editor (just for a test)? Maybe there is a bug in the ui that makes it not detecting the map has been updated when re-importing the map.

@matlabbe
Copy link
Member

The Export/Import workflow seems working. Here the output after closing and reloading rtabmap-databaseViewer (I put a "T" in the middle with GIMP editor):
Screenshot from 2022-12-12 22-51-53

@dimitryn
Copy link

@matlabbe thanks it working now.

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

No branches or pull requests

4 participants