how is external odometry added to graph?

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

how is external odometry added to graph?

Geert Folkertsma
I'm a bit lost after going through the codebase, so I hope someone here can give me a pointer where to look.

I'm trying to find out how the external odometry (e.g. from robot_localization) is added to the graph. I'm especially interested in how the covariance of the odometry message is used; and how multiple odometry messages between nodes/signatures(right?) are combined into a constraint.

Can someone point me to some places in the code where the odometry comes in (ros subscriber), and through which path it gets added to the graph? I've found some bits and pieces, but the complete path is not clear to me.

In my use case, rtabmap also receives laserscan data (which it may use for proximity matches or not), and gps measurements (which it may use with ignorePriors=false). I want to better understand how increasing covariance of the robot_localization's EKF (no corrections, after all) ends up in the graph.
Reply | Threaded
Open this post in threaded view
|

Re: how is external odometry added to graph?

matlabbe
Administrator
I'll make the example with ros1 branch, though on ros2 branch you should find the same code.

First of all, if odom_frame_id parameter is set to rtabmap node, it won't subscribe to any odometry topic, it will just use TF to get the pose and the covariance will be fixed by odom_tf_linear_variance and odom_tf_angular_variance parameters.

In your case, when rtabmap is subscribed to the odometry topic, between two rtabmap updates, it will keep only the largest twist's covariance for the next rtabmap's update. This is done in this function: https://github.com/introlab/rtabmap_ros/blob/ef8ec4357d76fc83351acfaff0fc31c778214f46/rtabmap_slam/src/CoreWrapper.cpp#L1090C1-L1094

That callback is not called for every odometry topic, but only those that have been synchronized with the input sensor data. For example, if rtabmap subscribes to camera images at 30 Hz, lidar scans at 10 Hz and odometry at 50 Hz, the callback will be called only at 10 Hz, so only 10 of 50 odometry topics will be processed. With RTAB-Map's detection rate set to 1 Hz (default), only the largest twist covariance of these 10 odometry topics will be added to the map's graph.

Instead of keeping only max covariance at line 1093 in the link above, integrating them could be better. We could do something similar to what we do here to update localization pose's covariance by integrating odometry's covariance. That way, the 10 odometry topics (in the example above) would be integrated together.