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

How to integrate external map->odom transform into rtabmap?

asked 2023-02-26 02:52:47 -0600

updated 2023-02-27 12:25:23 -0600

Hi, I have a question about localization of a robot and integrating rtabmap_ros with an external localization source that provide map->odom transform.

I have an instance of the robot_localization package that combine information from wheel encoders and visual odometry to provide the odom->base_link transform.

Then there is another custom node that combine information from landmarks with the previous localization source and output a map->odom tf. The output position is in the map frame because it is not continous.

Moreover I have the rtabmap node that generates the map, but it also output the map->odom tf.

So my questions are:

  • If I disable the map->odom publishing of rtabmap, to use only the one from the custom node, will rtabmap still be able to detect loop closure and optimize the map?
  • There is a way to integrate correctly the map->odom tf published by the other node into rtabmap?

I found this question that is related: https://answers.ros.org/question/2256... But it is quite old and I don't know if now there is a better way to do this.

I am using ROS Noetic

edit retag flag offensive close merge delete

Comments

1

Hopefully this is the answer you are looking for. AMCL and rtabmap are only to correct for errors in wheel odometry and visual odometry in your case. What you should be doing is the visual odometry + the wheel odometry node broadcasts odom -> base_link and rtabmap broadcasts map -> odom to adjust for errors. This is because rtabmap is very jumpy and would not be very reliable and wheel odometry + visual odometry is very smooth. this video explains this very well (watch starting at 3:22 ROS and SLAM video chapter. This is for ROS 2 not ROS 1) https://www.youtube.com/watch?v=ZaiA3...

bribri123 gravatar image bribri123  ( 2023-02-28 20:14:54 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2023-03-02 20:49:52 -0600

matlabbe gravatar image

For your first question, rtabmap will still detect loop closures, but the map frame inside of the map topic won't mean the same thing than external TF map frame. The map may look odd in rviz.

For your second question, the short answer: you can't.

The long answer, it depends what is represented by your external map->odom, thus some other data can be fed to rtabmap instead:

  • If your external map->odom is coming from another SLAM system (that is working in its own reference frame), there is not that much you can do, as both SLAMs will drift differently from each other (as they won't detect the same loop closures). You would have to chose one or the other.
  • If the external /map -> /odom represents a world frame (e.g., combined GPS + wheel odometry using robot_localization package), you may feed the pose /map -> /base_link of that system as global_pose input topic to rtabmap node, which will use it as prior. The internal graph will optimized in that coordinate frame, thus /map -> /odom published by rtabmap will include your external global pose estimation. The TF from that external node would have to be disabled, and let rtabmap provide /map -> /odom.
  • If your external pose is GPS, feed it /gps/fix as input topic of rtabmap.

In localization mode, you can disable /map -> /odom published from rtabmap, and feed its localization_pose to some other node doing fusion with other global poses.

edit flag offensive delete link more

Comments

Thanks for the answer, I'll try your suggestion :)

AlessioParmeggiani gravatar image AlessioParmeggiani  ( 2023-03-06 03:48:02 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2023-02-26 02:52:47 -0600

Seen: 498 times

Last updated: Mar 02 '23