Hello Mathieu,
I keep my database on disk in case something happens to the system (crash, power etc). So in case I have to bring up the database again without having had the chance of doing rtabmap::close() I have noticed that visual words can't be loaded from the database. I get 1000's of this "VWDictionary addWordRef() Not found word X (dict size=0)" but the signatures load fine. Going through the log and code I can also see that visualwords are only saved to the database at database close, via Rtabmap::Close() -> Memory::close() -> Memory::clear() -> moveToThrash() The signatures are saved correctly with Memory::saveLocationData() at the end of Rtabmap::process() How come the visual words cannot be saved in a simliar manor? (Or why are they not save together with the signature? ) I have tried to naively just to run asyncsave and emptyThrash with the !isSaved words from the dictonary but I run into various pit falls of exceptions or seg faults. Any suggestions on how to get the visualwords properly saved without doing close is appreciated (I think bidirectional links could have a simliar problem as I only . see one direction when loaded after not doing close) Thanks! |
Administrator
|
This post was updated on .
Hi,
Since RTAB-Map 0.16.3, we added a tool called rtabmap-recovery. Its purpose is to recover a database in case the robot has lost power or that rtabmap could not properly close (e.g. crash). By default the database in ROS is saved in ~/.ros/rtabmap.db. After a crash/shutdown, do: $ rtabmap-recovery ~/.ros/rtabmap.db Memory::saveLocationData() is saving only the node data, not the relations with other signatures/links/dictionary like Memory::moveToTrash() is doing. When a crash occurs, all info about the graph and the dictionary are lost. When we reload the corrupted database, we would get "VWDictionary addWordRef() Not found word X" warnings and the map's graph would not exist. Using rtabmap-recovery is currently the only way to recover such cases. To save the whole state of the map on runtime, call the backup service periodically: $ rosservice call /rtabmap/backupThis can be however not fast, as the whole database should be saved, then reloaded (similarly to close and re-open the database). See http://wiki.ros.org/rtabmap_ros: cheers, Mathieu |
Hi,
I'm not using the ROS package of rtabmap, I'm using the RtabMap API directly. I have previously looked at the recovery but I got into issues with SQL corruption but I will give it another chance to see how it goes. Thanks, SB |
Administrator
|
You can look at how the backup works in ros if you interested to try this approach with the API:
https://github.com/introlab/rtabmap_ros/blob/b09ff6c51170425c83f18e5c80c88338cd09b87b/src/CoreWrapper.cpp#L2531-L2558 Mainly: rtabmap_.close(); UFile::copy(databasePath_, databasePath_+".back"); rtabmap_.init(parameters_, databasePath_); cheers, Mathieu |
This post was updated on .
I tried the close->copy to backup->init but after some time and many more RGBD data it becomes very slow as you mention (takes a minute or more actually). But it works!
I got recovery to work but I must have kMemBinDataKept=true I assume this is necessary as it has to re-extract features from the images for the visual words? Would it at all be possible to not keep the images in the database? As it becomes gigabytes after a 1000 RGBD pairs in VGA size instead of hundreds of MB with no images stored in the database. |
Administrator
|
Hi,
Thx for the suggestion, I updated the code to be able to recover databases where Mem/BinDataKept is false. The features were indeed backup after each map update, so I just needed to republish those features when recovering the database. If RGBD/CreateOccupancyGrid is true, the occupancy grid should be also recopied to recovered database. cheers, Mathieu |
Free forum by Nabble | Edit this page |