ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

rtab_map localization tuning & goal setting questions

asked 2021-11-03 20:56:26 -0500

kiprock gravatar image

updated 2021-11-03 21:00:08 -0500

A couple of questions concerning rtab_map localization:

  1. During localization, how can I tune rtab_map to not make big jumps on the map in once the system has had a confident localization?
  2. Do I need to update cache from local database copy in the Rtab map visualizer, even though I specify the db file in my launch?
  3. What combination of sensors results in the very best map creation?
  4. What combination of sensors results in the very best localization?
  5. I see that RTAB subscribes to goal and also provides a set_goal service. I am not sure how this works with move_base local/global planners. Could someone please provide a little more detail on this?

Thanks!!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-11-08 10:01:56 -0500

matlabbe gravatar image

updated 2021-11-08 10:02:56 -0500

Hi,

  1. RTAB-Map follows REP105 for map frame, thus will produce discrete jumps when a loop closure or relocalization happens. Thinking of localizations like a GPS, you may look at this example to filter the localization poses (using robot_localization package). Another solution is to set RGBD/OptimizeFromGraphEnd parameter to true: the robot won't jump anymore, but it is the map that will jump around. Also, the global pose will drift over time (as odom will be the global frame), so if you plan to use metric goals for autonomous navigation to plan in map frame, you would have to pass by rtabmap's goal interface so that the pose can follow the graph (like in this paper).

  2. You can do "Download Map" in rtabmapviz. However, if the map is too big, the download time would be too high and may fail (ros services are limited). The local database copy is a way to update rtabmapviz without downloading the map from rtabmap node. If it is not convenient for your application (as it requires to copy offline the database between the computers), you may then transfer to RVIZ, and subscribe to topics like cloud_map. Note that if you want the high resolution point clouds using rtabmap_ros/MapCloud RVIZ plugin, there is a new way to incrementally republish the whole map, see this post. This approach is still yet to be implemented with rtabmapviz.

  3. It depends if you are in 2D or 3D, weight, size, cost and computation power of the robotic platform. In this paper, we compared Stereo vs 3D LiDAR for the 3D case, then RGB-D vs Stereo vs 2D LiDAR (short-range and long-range) for 2D mapping. Note that dense maps / occupancy grids would be more accurate with LiDAR-based mapping, while trajectory accuracy may be similar between LiDAR-based or Vision-based approaches (but that depends always of the environment, if it has a lot of geometric constraints required by LiDAR or visual textures and enough lighting required by vision).

  4. See 3.

  5. This is explained in this paper. RTAB-Map's goal interface is an intermediary between the module sending the goal and move_base. The goal can be metric or a node in the graph (even a label "kitchen") which will be translated to a metric goal. The metric goal is attached to closest node in the graph, so if the graph is deformed because of a loop closure, the goal will be republished to move_base with the new location matching the optimized map. This is essential useful only in SLAM mode. For the localization mode (with default RGBD/OptimizeFromGraphEnd=false), you could send directly your metric pose to move_base, as the map is fixed and will never change.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-11-03 20:56:26 -0500

Seen: 254 times

Last updated: Nov 08 '21