Hi Chris,
Thx for sharing the data.
When using the bag, you may want to decompress before playing it to avoid lags ("rosbag decompress ..."). Otherwise, rtabmap was complaining about missing TF, in particular base_footprint and /stereo/left frames. I added them manually like this based on existing frames:
<node pkg="tf" type="static_transform_publisher" name="base_footprint_to_base_link" args="0 0 0 0 0 0 base_footprint base_link 100"/>
<node pkg="tf" type="static_transform_publisher" name="left_to_stereo_left" args="0 0 0 0 0 0 left /stereo/left 100"/>
Ideally, you have to fix your URDF file.
I also see that you have an IMU, you can compute the quaternion and feed it to stereo_odometry and rtabmap nodes like this:
<node pkg="imu_filter_madgwick" type="imu_filter_node" name="imu_filter_node">
<remap from="imu/data_raw" to="/imu"/>
<param name="publish_tf" value="false"/>
<param name="use_mag" value="false"/>
</node>
<node pkg="rtabmap_odom" type="stereo_odometry" name="stereo_odometry" output="screen">
[...]
<param name="wait_for_transform" type="bool" value="true"/>
<remap from="imu" to="/imu/data"/>
</node>
<node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="--delete_db_on_start">
[...]
<remap from="imu" to="/imu/data"/>
<remap from="gps/fix" to="/gps/fix"/>
</node>
Note that I also took the liberty to feed GPS topic to rtabmap too, so that we can export the poses in KML format with rtabmap-databaseViewer and also compare trajectory (blue) with GPS (green):
![](http://official-rtab-map-forum.206.s1.nabble.com/file/n9419/Screenshot_from_2023-04-19_22-36-04.png)
![](http://official-rtab-map-forum.206.s1.nabble.com/file/n9419/Screenshot_from_2023-04-19_22-28-37.png)
![](http://official-rtab-map-forum.206.s1.nabble.com/file/n9419/Peek_2023-04-19_22-41.gif)
Regards,
Mathieu