MemoryThr

classic Classic list List threaded Threaded
10 messages Options
Reply | Threaded
Open this post in threaded view
|

MemoryThr

dnozik
Hi Mathieu,
I would like your advice regarding tunning the ‘MemoryThr’, in order to utilize the long-term memory mechanism. There is clearly an accuracy-performance tradeoff with this parameter, as when I keep all the nodes in the working memory, I get the best accuracy, but the performance decreases due to the large map size in memory.
Could you please suggest a way to set ‘MemoryThr’ value based on the planned trajectory size of the expected mapping session, or based on the known warehouse size?
Thanks
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

matlabbe
Administrator
In general I prefer to set "Rtabmap/TimeThr` to adjust depending on the computation power available (e.g., setting Rtabmap/TimeThr=0.7 when Rtabmap/DetectionRate=1), though "Rtabmap/MemoryThr" can give more similar results on different computers (as it is independent of the computation power). Both parameters will trigger memory management approach of RTAB-Map. When using memory management, we should use RGBD/OptimizeFromGraphEnd to true to avoid the robot to jump, this makes the map always transformed in odom frame (/map->/odom will be always identity). The parameter "Mem/RehearsalSimilarity" should also be carefully tuned, not too high or too low otherwise always old nodes from WM will be transferred to LTM first, removing the ability to find loop closures on old nodes. In general, to tune it I would do a mapping session and check "Memory -> Rehearsal sim" statistics:


In this case, I would set the parameter to "Mem/RehearsalSimilarity=0.2" so that the weight of the nodes (over that threshold) are uniformly distributed in the environment while not adding too many of them.

For path planning to an area that is transferred in LTM, you would have to call "/rtabmap/set_goal" service to a known node id or label:
rosservice call /rtabmap/set_goal "node_id: 0
node_label: ''
frame_id: ''"

To make it easier, I'll suggest to label important locations while mapping (e..g, "aisle_1_B", "aisle_1_C", "aisle_2_A"...), so that when the robot has to go to "aisle_1_B", we call:
rosservice call /rtabmap/set_goal "node_id: 0, node_label: 'aisle_1_B', frame_id: ''"
On success, rtabmap will make sure to transfer back nodes from LTM to WM to be able to localize while following the path (successive goals are published on /rtabmap/goal_out). To more in-depth details, see this paper on how it can be integrated with move_base: "Long-Term Online Multi-Session Graph-Based SPLAM with Memory Management"

General thoughts: Note that if you are planning to map the whole warehouse, then use the map in localization mode, and if you don't care to actually see in real-time the loop closure detected while mapping, you could disable loop closure detection (Kp/MaxFeatures=-1) and just make rtabmap accumulate the nodes in the database. Offline, use `rtabmap-reprocess` while re-enabling loop closure detection (adding option "--Kp/MaxFeatures 500") to remap without memory management. In localization mode, rtabmap should be able handle online very large maps without the need of memory management. The memory management approach is mostly useful when we want to do continuous SLAM.

cheers,
Mathieu
AD
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

AD
Could you help explain a bit more regarding the two changes you mentioned here?
- When using memory management, we should use RGBD/OptimizeFromGraphEnd to true to avoid the robot to jump, this makes the map always transformed in odom frame (/map->/odom will be always identity)
> if the /map -> /odom will be always identity, how do we fix/eliminate the accumulated odom error while calculating robot pose(/base_link -> /map)?

- The parameter "Mem/RehearsalSimilarity" should also be carefully tuned, not too high or too low otherwise always old nodes from WM will be transferred to LTM first, removing the ability to find loop closures on old nodes
> it seems this parameter is affecting the rehearsal merge feature, how does it affecting the nodes transferring from WM to LTM?

Thank you.
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

matlabbe
Administrator
When RGBD/OptimizeFromGraphEnd is true, the accumulated errors is corrected not by changing the robot position but by changing the map position in relation to odom frame. That means that instead having the robot jumping in a map, the map is jumping to current odometry position when there is a loop closure or re-localization.

For the similarity threshold, if you look at the figure of my previous post, setting it to 0.2 would mean that all nodes under that threshold will be moved to LTM before those over the blue line. When similarity is over that blue line, it means the "weight" of that node increased. From Section III, 3rd paragraph:

When a transfer from WM to LTM is necessary, the location with the lowest weight is selected. If many locations have the same lowest weight, the oldest one is transferred.
AD
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

AD
This post was updated on .
thank you. for the Mem/RehearsalSimilarity I understand better now.

For the RGBD/OptimizeFromGraphEnd, I still don't quite get it, especially in localization mode:
> if working in localization mode and robot is moving from A->B, normally A and B are stated in map frame, if setting RGBD/OptimizeFromGraphEnd to true, it means the robot pose is not jumping in map frame, but A and B poses(in map frame) are changing accordingly?
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

matlabbe
Administrator
This post was updated on .
Here is an example in localization mode.

The robot just initialized (map == odom frame) and received a goal for node 121, with pose x=30,y=40 in map frame. While navigating towards that goal, the robot relocalizes on the map on a node 2 meters from where it thinks it is.

If RGBD/OptimizeFromGraphEnd=false, the robot pose will jump 2 meters in map frame to correct this odometry drift (that 2 meters will be included in map -> odom TF), and node 121 will still be at x=30, y=40 in map frame. This follows the definition of map->odom TF in ROS.

If RGBD/OptimizeFromGraphEnd=true, the robot pose in map/odom frame will stay the same (map == odom frames), but the node 121 will jump 2 meters instead. The goal will then be at x=32,y=40.

When we use memory management, the root node for map frame can change anytime, thus it would make the node poses jumping around AND make the robot pose jumping around. This can hard to handle robot pose jumping and map nodes jumping at the same time. With RGBD/OptimizeFromGraphEnd=true, at least the robot pose doesn't jump.
AD
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

AD
thanks I understand what you are saying, but still some questions:

1. in localization mode, when we are doing graph optimization, are we fixing the poses of all the nodes from the saved map(not just root/the oldest one)?
2. if that's the case, I don't see we have all the poses saved in db if LTM is enabled, we only kept a specific number of _optimizedPoses in db(which is the local map?).
3. if that's not the case, how does the localization work if we are still optimizing the poses of saved nodes?
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

matlabbe
Administrator

In localization mode, the local graph is optimized only if there is a retrieval from LTM to WM, using oldest node in WM as root.

The optimizedPoses saved in the database are the poses corresponding to WM at that time (e.g., the local map).

I think I understand what you are implying. It could be indeed a nice option if we could save the full WM+LTM optimized graph in database (or do single global map optimization on start with all nodes in WM and LTM when launching in localization mode) so that the root is always the oldest node in the database. On retrieval, we don't need to optimize anything anymore that would make the map origin to change, we just take the pose from the WM+LTM optimized graph. The poses will be always in same map frame even if memory management is enabled (so we can use RGBD/OptimizeFromGraphEnd=false).

I added a new issue about that: https://github.com/introlab/rtabmap/issues/1245
AD
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

AD
if we go this way(load the full optimized graph), it seems there's lots of things to be changed, I see the optimized poses are also being pruned if we enable LTM, right?

Also, we still need graph optimization, but only keep the old nodes(loaded from db) as fixed, so we can optimize the new poses in current localization session, right?
Reply | Threaded
Open this post in threaded view
|

Re: MemoryThr

matlabbe
Administrator

Hi,

The pruning in local graph can remain there when a node is transferred to LTM. I don't think there is much code to disable/ignore, only code to re-add the poses of retrieved nodes (LTM->WM) into the local graph based (_optimizedPoses) on the ones in a cached global graph (initialized on start maybe here) without re-optimizing the local map's graph. I think that could be done at the end of this section, then inhibit all checks below to signaturesRetrieved.size() or signaturesRetrieved.empty() to make sure map graph optimization is not done.

The optimization for the localization graph (odom cache) will still be done.

cheers,
Mathieu