Running RTAB Map breaks my TF Tree
I am running rtab map on my create 3 with a jetson orin nano host computer with jetpack6 and ros humble. Without rtabmap running I have the following TF tree frames_2024-12-11_18.31.10.pdf
When I run rtab map in localization mode with the following launch file
from launch import LaunchDescription
from launch.actions import GroupAction
from launch_ros.actions import Node, PushRosNamespace
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
import os
def generate_launch_description():
return LaunchDescription([
GroupAction(
actions=[
PushRosNamespace('rtabmap'),
Node(
package='rtabmap_slam',
executable='rtabmap',
name='rtabmap',
output='screen',
prefix=['taskset -c 0-2'], # Restrict to 3 cores
parameters=[{
'frame_id': 'base_link',
# Localization mode parameters
'Mem/IncrementalMemory': "False",
'Mem/InitWMWithAllNodes': "True",
# Database path
'database_path': os.path.expanduser('~/.ros/rtabmap.db'),
# TF parameters
'publish_tf_map': True,
'odom_frame_id': 'odom',
'map_frame_id': 'map',
'tf_delay': 0.5,
'map_always_update': True,
# Subscription settings
'subscribe_depth': False,
'subscribe_rgb': False,
'subscribe_rgbd': True,
'subscribe_scan': True,
# Queue sizes
'sync_queue_size': 80,
'topic_queue_size': 100,
# Parallel processing parameters
'RGBD/NeighborLinkRefining': "True",
'RGBD/ProximityBySpace': "True",
'RGBD/AsyncBundleAdjustment': True,
'Optimizer/Slam2D': True,
'Optimizer/ThreadsCount': 2,
'Vis/FeatureThreadsCount': "2",
'Vis/EstimationType': "1",
'Vis/CorNNThreads': "2",
# Movement thresholds
'RGBD/LinearUpdate': "0.10",
'RGBD/AngularUpdate': "0.087",
'RGBD/DetectionRate': 1.5,
# CPU optimizations
'RGBD/OptimizeFromGraphEnd': "False",
'Grid/Sensor': 'scan',
'Reg/Force3DoF': "True",
'Reg/Strategy': "2",
# Point cloud processing
'Icp/VoxelSize': "0.15",
'Icp/MaxCorrespondenceDistance': "0.2",
'Icp/ThreadsCount': 2,
# Memory and feature parameters
'RGBD/MaxLocalFeatures': 600,
'Mem/STMSize': "12",
'Mem/BadSignaturesIgnored': "False",
# Feature parameters
'RGBD/MaxFeatures': 600,
'Vis/MinInliers': "10",
'Optimizer/Iterations': "10",
# Additional parallel processing
'RGBD/PoseScanMatching': True,
# Added parameters
'RGBD/StartAtDock': False,
'init_pose_x': 0.0,
'init_pose_y': 0.0,
'init_pose_z': 0.0,
'init_pose_yaw': 0.0,
}],
remappings=[
('odom', '/odom'),
('scan', '/scan'),
('rgbd_image', '/rgbd_image'),
('tf', '/tf'),
('tf_static', '/tf_static'),
]
),
]
),
# Startup node
Node(
package='rtab_nav',
executable='rtab_startup.py',
name='rtab_startup',
output='screen'
)
])
The TF tree breaks and I get
frames_2024-12-11_18.30.41.pdf
Would appreciate some help on what I am doing wrong, tried everything else
I also notice that the rtab map node does not subscribe to odometry despite it existing and it being published
The missing link between odom and base_link is not published by rtabmap but by probably your create3 driver. You can double check why odom->base_link is not published anymore.
For rtabmap config, if you set explicitly 'odom_frame_id': 'odom', rtabmap won't subscribe to odom topic, but just get it from TF and use odom_tf_linear_variance/odom_tf_angular_variance parameters to set the odometry covariance matrix. Remove odom_frame_id and it will subscribe to odom topic (and use covariance form that topic).