rtabmap_ros icon indicating copy to clipboard operation
rtabmap_ros copied to clipboard

Localization Issue when Mapping Similar Multiple Floors.

Open brayanpa opened this issue 2 years ago • 3 comments

I am trying to map multiple floors that are very similar to each other. For this purpose, I am creating a session for each floor, and It works fine as long as it doesn't see features of another floor. I have been reading and came across the GridGlobal/AltitudeDelta parameter, which I believe could help me with this issue. I have set this parameter to 2.0 and verified that the odometry changes in the Z-axis when transitioning between floors (around 4.0 meters for each floor). However, even with this setting, the robot can still localize itself on the wrong floor.

For example, when the robot is on the fourth floor with a Z-axis odometry value of 12 meters and the GridGlobal/AltitudeDelta parameter set to 2.0, it may erroneously localize itself on a different floor.

I would greatly appreciate your assistance since I could not find much documentation regarding this specific case or the mentioned parameter. Therefore, I am unsure if I am configuring it correctly. Thank you very much.

brayanpa avatar Jul 12 '23 18:07 brayanpa

From the doc:

Param: GridGlobal/AltitudeDelta = "0" [Assemble only nodes that have the same altitude of +-delta meters of the current pose (0=disabled). This is used to generate 2D occupancy grid based on the current altitude (e.g., multi-floor building).]

That parameter is used only to assemble the 2D occupancy grid depending on altitude. It won't affect how loop closure is done. Ideally, the wrong loop closures between different floors would be detected by RGBD/OptimizeMaxError and then rejected. You may try decreasing RGBD/OptimizeMaxError value. However, the odometry covariance should be carefully tuned to make it work properly. The idea behind RGBD/OptimizeMaxError is that after loop closure detection, if the graph is deformed more than X time the covariance error in the links, the loop closure will be rejected. So if covariance is over estimating the real error, the loop closure may still be accepted.

matlabbe avatar Jul 14 '23 16:07 matlabbe

Thank you Mathieu for your quick response.

Now I understand the parameter "GridGlobal/AltitudeDelta", but I'm afraid that the parameter "RGBD/OptimizeMaxError" will not help me since my current idea is to map each floor in a different session (without connecting between them). Therefore, when the robot localizes itself, it builds the map of the floor where it is. Correct me if I'm wrong but I understand that this is possible. The problem I have is that the floors are very similar so when mapping a floor the robot might erroneously perceive it as a continuation of a previously mapped floor. I understand that in this case there would be no deformation of the graph since the sessions are not connected.

Is there any parameter that could help me tell the robot which floor it is on? I had the idea to fake the altitude of the gps by reading some apriltag on each floor, but this had no effect. I appreciate any suggestions.

brayanpa avatar Jul 17 '23 20:07 brayanpa

That is a difficult one, the current code doesn't really support an altitude range for loop closures. The hack approach using GPS altitude would not work as altitude is actually ignored.

To feed the correct Z in the optimized graph (with Optimize/PriorsIgnored=false), maybe global_pose topic could be used instead by setting the floor level in z. Setting high covariance to all other parameters (in particular setting >=9999 for rotation parameters, optimizer will just use x-y-z in the graph as priors). If covariance of z is very small, normally during optimization on a loop closure between 2 floors, it won't deform the graph between the floors, creating a large loop closure transform that would be rejected.

matlabbe avatar Jul 31 '23 00:07 matlabbe