Hi,
We want to use WM/STM in localization mode as our databases are very big. Is there any difference for memory management (WM/STM/LTM) in localization vs mapping mode or it's exactly same? What params to recommend to refine? thanks |
Administrator
|
If you enable memory management (e.g., by setting Rtabmap/TimeThr or Rtabmap/MemoryThr), rtabmap should behave the same in localization vs mapping modes. When using memory management, it is also better to set "RGBD/OptimizeFromGraphEnd" to true:
This makes map and odom frames the same (on relocalization, the map is moved instead of the pose updated). Refer to this paper to see all the implications there are on navigation when memory management is enabled. cheers, Mathieu |
can we load all nodes for graph optimization but dont load full vocabulary to save memory?
we work with nav2 for navigation. is it possible load (to WM) all nodes that are close to the path provided by nav2 planner or load nodes within specific radius assuming graph optimization is done upon init ? |
Administrator
|
Hi,
I see what you would want but it is not possible right now. Indeed the graph is kinda small in RAM, while loading all the visual features / vocabulary can require significant memory. Having the option to load the global graph but load only vocabulary matching the WM state is an interesting idea (then update/resize the vocabulary when nodes are brought back in WM). In localization mode in particular, we could have a very low memory footprint. I created an issue about that. When rtabmap is restarted, it will load at least nodes to last known position of the robot. If the robot is starting somewhere else that is not in its working memory, it won't be able to correctly assemble the map around the current location without being localized first in a node in WM. Note also that I don't have an example of memory management enabled with nav2 stack (as I had with nav for ros1). To make rtabmap correctly loads appropriate nodes to WM based on nav2 planning (while following a path like int this paper), we should use "goal" topic input of rtabmap to send goal indirectly to nav2. Some code have been ported to ros2, but I think I never tested with memory management enabled. |
Mateu,
it's still not clear to me when you work with internal rtabmap navigation, do you know to load relevant nodes into WM based on proximity or still memory management loads nodes based on rehearsal similarity? I'm looking for a way to load nodes (in localization mode only) which are close to the current position and navigation path. thanks |
Administrator
|
Hi,
In all cases, rtabmap will always retrieve nodes around the best loop closure hypotheses, independently of the current position of the robot in the map. This is useful in case the robot is lost (may not know it) and globally re-localize. This is done here. When we use rtabmap planning capabilities as an intermediate to move_base, it will know which nodes in the global map to follow to reach the goal. If the nodes on that path are in LTM, they will be retrieved back to WM as the robot follows the planned path (i.e., series of nodes to reach the goal). This is done here. If we didn't reach the number maximum local nodes retrieved (RGBD/MaxLocalRetrieved), we also look for the closest nodes. This is done here. The last two cases seem do to already something similar to what you said: "close to the current position and navigation path". We can adjust how many nodes at each update could be retrieved around the current position of the robot, by default it is 2. rtabmap --params | grep Retrieved Param: Rtabmap/MaxRetrieved = "2" [Maximum nodes retrieved at the same time from LTM.] Param: RGBD/MaxLocalRetrieved = "2" [Maximum local locations retrieved (0=disabled) near the current pose in the local map or on the current planned path (those on the planned path have priority).] cheers, Mathieu |
Free forum by Nabble | Edit this page |