Posted by
matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Rtabmap-mapping-done-but-can-t-do-relocalization-tp1257p1271.html
Hi,
For
Autonomous Navigation section, you can look if move_base is publishing velocity when dropping a goal in RVIZ:
$ rostopic echo /mobile_base/commands/velocity
If not look for move_base/planning errors on the terminal. Sometimes move_base would say that it cannot plan if there is a problem with receiving sensor messages. This topic should be somewhat connected to base controller of turtlebot.
Warnings:You can show the TF tree to see actual frequency of each frame (to make sure that they are really at 10 Hz with the change):
$ rosrun tf view_frames
$ evince frames.pdf
If they are really at 10 Hz, maybe the wait_for_transform parameter is two close to 10 Hz (set to 0.1 s). You can increase
wait_for_transform to 0.2.
a) "Odometry is reset (identity pose detected)." Until the robot is moving, it may appear a lot on start. This is fixed in recent versions.
b) "Refinement failed: got an empty set of inliers!" Yes, it is a normal warning as mentioned in previous post.
c) "Not enough correspondences found. Relax your threshold parameters" This is related to local loop closure detection using ICP. Actually, it is a warning coming from PCL library. Not the issue here for navigation.
For part of the map disappearing, it is related to memory management approach of RTAB-Map (explained in details in the
papers). You can disable memory management to keep all point clouds, however map update time will not be bounded.
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap">
<param name="Rtabmap/TimeThr" type="string" value="0"/> <!-- 0 means memory management disabled -->
</node>
rtabmap sends always nodes contained in the current map of the Working Memory. If the Working Memory contains all nodes of the global map, then the full global map should be shown. However, when memory management is enabled and the time limit is reached, not all nodes would be in Working Memory (some are transferred in Long-Term Memory) so some parts may be missing in the published map. Note however that revisiting close areas of this missing parts would make them retrieved back into Working Memory, so publishing them.
When setting RTAB-Map in localization mode, you may safely set:
<!-- localization mode -->
<param if="$(arg localization)" name="Rtabmap/TimeThr" type="string" value="0"/>
<param unless="$(arg localization)" name="Rtabmap/TimeThr" type="string" value="700"/>
<param if="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="false"/>
<param unless="$(arg localization)" name="Mem/IncrementalMemory" type="string" value="true"/>
<param name="Mem/InitWMWithAllNodes" type="string" value="$(arg localization)"/>
The above disables memory management in localization mode, set fixed memory and make sure that all nodes from Long-Term Memory (database) are in Working Memory.
cheers,
Mathieu