RTAB-Map + OAK-D Pro in ROS 2 Humble — Can't connect base_link to camera TF, timestamp sync issues, and no map in RViz

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

RTAB-Map + OAK-D Pro in ROS 2 Humble — Can't connect base_link to camera TF, timestamp sync issues, and no map in RViz

dannym
I'm trying to set up RGB-D SLAM using RTAB-Map with the OAK-D Pro camera on ROS 2 Humble and encountering three major issues:

1. TF connection error:
Could not find a connection between 'base_link' and 'oak_rgb_camera_optical_frame'
because they are not part of the same tree. Tf has two or more unconnected trees.




2. Timestamp sync errors:
The time difference between rgb and depth frames is high (diff=0.066703s ...)



3. No map displays in RViz, even though odometry appears to work.



System Setup
• Robot computer: Jetson AGX Orin, ROS 2 Humble, Ubuntu 22.04

• Camera: OAK-D Pro

• Camera launch command:

ros2 launch depthai_ros_driver camera.launch.py params_file:=/home/danny/depthai_config/oak_sync.yaml

• RTAB-Map launch command:

ros2 launch rtabmap_launch rtabmap.launch.py \
  rgb_topic:=/oak/rgb/image_raw \
  depth_topic:=/oak/stereo/image_raw \
  camera_info_topic:=/oak/rgb/camera_info \
  depth_camera_info_topic:=/oak/stereo/camera_info \
  odom_topic:=/odom \
  frame_id:=base_link \
  approx_sync:=true \
  rtabmap_args:="--Rtabmap/DetectionRate 1.0"

What's Working
• /odom is being published by my custom CAN-based odometry node.

• Camera topics are all publishing and appear with good ros2 topic hz rates:

/oak/rgb/image_raw           ~7–8 Hz
/oak/stereo/image_raw        ~6–7 Hz
/oak/rgb/camera_info         ~8.6 Hz

• rgbd_odometry is reporting good quality:

Odom: quality=351, std dev=0.0032m | 0.014 rad, update time=0.088, delay=1.0s

• Static TFs are defined in this file: winning_static_transforms.launch.py:

from launch import LaunchDescription
from launch_ros.actions import Node

def static_tf(x, y, z, roll, pitch, yaw, frame_id, child_frame_id):
    return Node(
        package="tf2_ros",
        executable="static_transform_publisher",
        name=f"static_tf_{child_frame_id}",
        arguments=[
            str(x), str(y), str(z),
            str(roll), str(pitch), str(yaw),
            frame_id, child_frame_id
        ],
        output="screen"
    )

def generate_launch_description():
    return LaunchDescription([
        static_tf(0,     0.287655, 0, 0, 0, 0, "base_link", "left_wheel_link"),
        static_tf(0,    -0.287655, 0, 0, 0, 0, "base_link", "right_wheel_link"),
        static_tf(0.41275, 0, 0, 0, 0, 0, "base_link", "caster_link"),
        static_tf(0.47625, 0, 0.24655, 0, 0, 0, "base_link", "oak_d_base_frame"),
        static_tf(0.02, 0, 0, 0, 0, 0, "oak_d_base_frame", "oak_d_frame"),
        static_tf(0, 0, 0, -1.5708, 0, -1.5708, "oak_d_frame", "oak_rgb_camera_optical_frame")
    ])

• ros2 run tf2_tools view_frames confirms a complete tree from odom → base_link → oak_rgb_camera_optical_frame via intermediate frames:

odom → base_link → oak_d_base_frame → oak_d_frame → oak_rgb_camera_optical_frame

What’s Going Wrong
1. TF Error: “Not part of the same tree”
Despite static transforms appearing in the TF tree, I keep getting this from rgbd_odometry and rtabmap:
MsgConversion.cpp:2010::getTransform() (getting transform base_link -> oak_rgb_camera_optical_frame)
Could not find a connection ... Tf has two or more unconnected trees.

2. Timestamp Sync Error
This happens constantly with:
The time difference between rgb and depth frames is high (diff=0.066s or 0.099s ...)

Even with approx_sync:=true and camera set to sync mode via:
i_enable_imu: false
i_enable_sync: true

3. No Map in RViz
RViz is set to:

• Fixed Frame: base_link
• Map topic: /map

But I only get:

Status: Warn — No map received

Even though RTAB-Map is producing:

rtabmap (2225): Rate=1.00s, RTAB-Map=0.20s, Maps update=0.0004s pub=0.007s

What I've Tried
• Verified all static transforms with view_frames and ros2 topic echo /tf_static

• Set approx_sync:=true in RTAB-Map

• Throttled detection with --Rtabmap/DetectionRate 1.0

• Added /odom → base_link transform and verified it updates in RViz

• Launched static TFs via custom launch file in a verified package (my_robot)

• Verified /map exists in ros2 topic list but never publishes

• Compared topic timestamps with ros2 topic echo /oak/rgb/image_raw/header and /oak/stereo/image_raw/header — timestamps are valid but up to 133ms apart

Any Ideas?
I'm not sure why:

• The TF error still happens despite all static transforms being defined and visible.
• The RGB/Depth sync fails even with sync enabled.
• No map is published in /map despite odometry and frames working.

Would really appreciate any help or insights. Happy to upload more logs if needed. Thanks!
Reply | Threaded
Open this post in threaded view
|

Re: RTAB-Map + OAK-D Pro in ROS 2 Humble — Can't connect base_link to camera TF, timestamp sync issues, and no map in RViz

matlabbe
Administrator
I think depthai_ros_driver already publishes the camera TF (with parent oak-d-base-frame): https://github.com/luxonis/depthai-ros/blob/9c1682aed12ca3f986d3d4a31d8ccf7b7295b7c3/depthai_ros_driver/launch/camera.launch.py#L185

You may just launch depthai_ros_driver and record the TF tree to know which TF frames are already there.

If you want to use wheel odometry only, you should call rtabmap.launch.py with visual_odometry:=false:
ros2 launch rtabmap_launch rtabmap.launch.py \
  rgb_topic:=/oak/rgb/image_raw \
  depth_topic:=/oak/stereo/image_raw \
  camera_info_topic:=/oak/rgb/camera_info \
  depth_camera_info_topic:=/oak/stereo/camera_info \
  odom_topic:=/odom \
  frame_id:=base_link \
  approx_sync:=true \
  rtabmap_args:="--Rtabmap/DetectionRate 1.0" \
  visual_odometry:=false

To use visual odometry, you should use wheel odometry as guess instead by setting odom_guess_frame_id:
ros2 launch rtabmap_launch rtabmap.launch.py \
  rgb_topic:=/oak/rgb/image_raw \
  depth_topic:=/oak/stereo/image_raw \
  camera_info_topic:=/oak/rgb/camera_info \
  depth_camera_info_topic:=/oak/stereo/camera_info \
  odom_topic:=/odom \
  frame_id:=base_link \
  approx_sync:=true \
  rtabmap_args:="--Rtabmap/DetectionRate 1.0" \
  odom_guess_frame_id:=odom \
  odom_topic:=vo

To set a maximum difference between rgb and stereo topics, add "approx_sync_max_interval:=0.02", or "approx_sync:=false". rtabmap expects RGB-D topics to be already time synced.

You can also compare with this example (though for this one to work for OAK-D Pro, you would also need to disable the IR emitter).

cheers,
Mathieu