rtabmap localization error

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

rtabmap localization error

Sonic1991
This post was updated on .
Hello, I am learning rtabmap. I faced such a problem, when I left the robot in navigation mode, I turn on the localization mode on the built map, but before that I physically move the robot to another point. When localization is launched, the robot cannot determine its position, how can I fix it.
Thanks for your reply!
rtabmap terminal:
[ WARN] (2021-02-24 19:05:35.997) util3d.cpp:604::cloudFromDepthRGB() Cloud with only NaN values created!
[ INFO] [1614168336.070593797, 849.795000000]: rtabmap (560): Rate=1.00s, Limit=0.000s, RTAB-Map=0.3982s, Maps update=0.0017s pub=0.0003s (local map=28, WM=28)
[ WARN] (2021-02-24 19:05:38.247) Rtabmap.cpp:2610::process() Rejected loop closure 53 -> 561: Not enough inliers 0/20 (matches=1) between 53 and 561
[ INFO] [1614168338.250034435, 851.044000000]: rtabmap (561): Rate=1.00s, Limit=0.000s, RTAB-Map=0.6364s, Maps update=0.0014s pub=0.0000s (local map=28, WM=28)
[pcl::IterativeClosestPoint::computeTransformation] Not enough correspondences found. Relax your threshold parameters.
[ WARN] (2021-02-24 19:05:40.158) Rtabmap.cpp:2610::process() Rejected loop closure 56 -> 562: Not enough inliers 0/20 (matches=1) between 56 and 562
[ INFO] [1614168340.161742494, 852.104000000]: rtabmap (562): Rate=1.00s, Limit=0.000s, RTAB-Map=0.6043s, Maps update=0.0012s pub=0.0000s (local map=28, WM=28)

Reply | Threaded
Open this post in threaded view
|

Re: rtabmap localization error

matlabbe
Administrator

Did you restart rtabmap in localization mode, or that you called the service to change to localization?

As it seems you are using a standard turtlebot environment, can you show the commands used to start the simulation do that we can reproduce the problem more easily.
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap localization error

Sonic1991
I run the simulation with the following commands:
terminal 1
~ $ export TURTLEBOT3_MODEL = waffle
~ $ roslaunch turtlebot3_gazebo turtlebot3_world.launch
And I run:
terminal 2
~ $ export TURTLEBOT3_MODEL = waffle
~ $ roslaunch rtabmap_ros demo_turtlebot3_navigation.launch
Then I make a map of the area and kill Terminal 2. Using the keyboard control of the robot, I change the position of the robot. Then I start the localization mode:
terminal 2
~ $ export TURTLEBOT3_MODEL = waffle
~ $ roslaunch rtabmap_ros demo_turtlebot3_navigation.launch localization: = true
As a result, I get the fact that the robot cannot localize its position.
(This problem also happens when I turn off the camera on a real robot and change its position.)
Reply | Threaded
Open this post in threaded view
|

Re: rtabmap localization error

matlabbe
Administrator
Hi,

In your case, the robot won't be able to localize alone with the camera even by teleoperating it on the same path than during mapping, as the environment is textureless.

To set a localization guess manually, you can use "2D Pose Estimate" button with its topic set to /rtabmap/initialpose.


If the guess is enough close to reality, you would see yellow "Local match" in rtabmapviz, meaning that scan matching is actually localizing on the map.



Note that if you close kill terminal 2, and restart it without having moved the robot, it should be correctly localized on startup (rtabmap assumes it is restarting from last saved localization from its previous session).

To deal with "kidnapped robot problem", the environment should have more discriminating textured surfaces (avoid textureless and repetitive patterns). To do global localization automatically without the camera, you could try AMCL, though it would also require a first guess to converge correctly (and faster).

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

Re: rtabmap localization error

Sonic1991
This post was updated on .
Thanks a lot for your answer, Mathieu.
Did I understand you correctly that I have no way to localize the robot from a new position (changed without the knowledge of rtabmap) using rtabmap localization mode? And for these purposes would it be better to use lidar and AMCL?
If so, how can I implement localization using lidar if I build a map using rtabmap?