Hi, I am trying to implement the OAK-D-lite camera on a Waveshare UGV using a Pi 5. Several implementations are done by the Waveshare team in ready-to-run launch files, but I am trying to create a new launch file that includes sensor data from both a 2D LiDAR and a depth camera (OAK-D lite) into a costmap.
My conclusion so far is that the topics /oak/stereo/image_raw and /oak/stereo/camera_info is published at different frequencies, resulting in synchronization warnings when launching Rviz. I expect the point cloud to be generated to the topic /oak/depth/points using the package depth_image_proc, but ros2 topic echo <topic> generated an output randomly after several minutes, and ros2 topic hz <topic> shows nothing.
The measured publish frequencies for /oak/stereo/image_raw and /oak/stereo/camera_info:
$$
root@ugvrpi:~# ros2 topic hz /oak/stereo/image_raw
WARNING: topic [/oak/stereo/image_raw] does not appear to be published yet
average rate: 0.851
min: 0.203s max: 2.148s std dev: 0.97266s window: 2
average rate: 1.132
min: 0.203s max: 2.148s std dev: 0.74924s window: 4
average rate: 1.366
min: 0.092s max: 2.148s std dev: 0.63443s window: 7
Croot@ugvrpi:~# ros2 topic hz /oak/stereo/camera_info
average rate: 11.294
min: 0.050s max: 0.135s std dev: 0.02261s window: 12
average rate: 11.066
min: 0.049s max: 0.205s std dev: 0.03529s window: 23
average rate: 11.370
min: 0.040s max: 0.205s std dev: 0.03199s window: 36
average rate: 11.516
min: 0.040s max: 0.205s std dev: 0.03015s window: 48
average rate: 11.422
min: 0.040s max: 0.205s std dev: 0.02910s window: 60
Croot@ugvrpi:~# ros2 topic hz /oak/depth/points
$$
The warning message when running my launch file slam_nav.launch.py:
$$
[component_container-14] [INFO] [1769525395.563744145] [oak]: Camera with MXID: 19443010819C0D7E00 and Name: 1.1 connected!
[component_container-14] [INFO] [1769525395.565356299] [oak]: USB SPEED: HIGH
[component_container-14] [INFO] [1769525395.611756602] [oak]: Device type: OAK-D-LITE
[component_container-14] [INFO] [1769525395.613875468] [oak]: Pipeline type: RGBD
[component_container-14] [INFO] [1769525395.873098177] [oak]: NN Family: mobilenet
[component_container-14] [INFO] [1769525395.994634242] [oak]: NN input size: 300 x 300. Resizing input image in case of different dimensions.
[component_container-14] [INFO] [1769525396.616787138] [oak]: Finished setting up pipeline.
[component_container-14] [INFO] [1769525398.520479923] [oak]: Camera ready!
[component_container-14] [INFO] [1769525398.521267491] [oak_container]: Load Library: /opt/ros/humble/lib/librectify.so
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/oak' in container '/oak_container'
[component_container-14] [INFO] [1769525398.526015416] [oak_container]: Found class: rclcpp_components::NodeFactoryTemplate<image_proc::RectifyNode>
[component_container-14] [INFO] [1769525398.526085398] [oak_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<image_proc::RectifyNode>
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/rectify_color_node' in container 'oak_container'
[component_container-14] [INFO] [1769525398.580671938] [oak_container]: Load Library: /opt/ros/humble/lib/librobot_state_publisher_node.so
[component_container-14] [INFO] [1769525398.583756522] [oak_container]: Found class: rclcpp_components::NodeFactoryTemplate<robot_state_publisher::RobotStatePublisher>
[component_container-14] [INFO] [1769525398.583816690] [oak_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<robot_state_publisher::RobotStatePublisher>
[component_container-14] [INFO] [1769525398.636735815] [oak_state_publisher]: got segment 3d_camera_link
[component_container-14] [INFO] [1769525398.636817576] [oak_state_publisher]: got segment oak
[component_container-14] [INFO] [1769525398.636835483] [oak_state_publisher]: got segment oak_imu_frame
[component_container-14] [INFO] [1769525398.636848243] [oak_state_publisher]: got segment oak_left_camera_frame
[component_container-14] [INFO] [1769525398.636862039] [oak_state_publisher]: got segment oak_left_camera_optical_frame
[component_container-14] [INFO] [1769525398.636872614] [oak_state_publisher]: got segment oak_model_origin
[component_container-14] [INFO] [1769525398.636881262] [oak_state_publisher]: got segment oak_rgb_camera_frame
[component_container-14] [INFO] [1769525398.636889781] [oak_state_publisher]: got segment oak_rgb_camera_optical_frame
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/oak_state_publisher' in container 'oak_container'
[component_container-14] [INFO] [1769525398.636899318] [oak_state_publisher]: got segment oak_right_camera_frame
[component_container-14] [INFO] [1769525398.636909336] [oak_state_publisher]: got segment oak_right_camera_optical_frame
[point_cloud_xyz_node-15] [WARN] [1769525400.704855446] [oak_pointcloud]: [image_transport] Topics '/oak/stereo/image_raw' and '/camera_info' do not appear to be synchronized. In the last 10s:
[point_cloud_xyz_node-15] Image messages received: 1
[point_cloud_xyz_node-15] CameraInfo messages received: 12
[point_cloud_xyz_node-15] Synchronized pairs: 1
[point_cloud_xyz_node-15] [WARN] [1769525402.705070974] [oak_pointcloud]: [image_transport] Topics '/oak/stereo/image_raw' and '/camera_info' do not appear to be synchronized. In the last 10s:
[point_cloud_xyz_node-15] Image messages received: 3
[point_cloud_xyz_node-15] CameraInfo messages received: 11
[point_cloud_xyz_node-15] Synchronized pairs: 3
$$
The /oak/depth/points topic info:
$$
root@ugvrpi :~ # ros2 topic info /oak/depth/points -- v
Type: sensor_msgs/msg/Pointcloud2
Publisher count: 1
Node name: oak_pointcloud
Node namespace: /
Topic type: sensor_msgs/msg/Pointcloud2
Endpoint type: PUBLISHER
GID: 01.0f.15.23.f6.46.4d.74.00.00.00.00.00.00.14.03.00.00.00.00.00.00.00.00
QoS profile:
Reliability: BEST EFFORT
History (Depth): UNKNOWN
Durability: VOLATILE
Lifespan: Infinite
Deadline: Infinite
Liveliness: AUTOMATIC
Liveliness lease duration: Infinite
Subscription count: 2
Node name: rviz2
Node namespace: /
Topic type: sensor_msgs/msg/PointCloud2
Endpoint type: SUBSCRIPTION
GID: 01.0f.15.23.16.46.7a.22.00.00.00.00.00.00.8b.04.00.00.00.00.00.00.00.00
QoS profile:
Reliability: BEST EFFORT
History (Depth): UNKNOWN
Durability: VOLATILE
Lifespan: Infinite
Deadline: Infinite
Liveliness: AUTOMATIC
Liveliness lease duration: Infinite
Node name: local_costmap
Node namespace: /local_costmap
Topic type: sensor_msgs/msg/Pointcloud2
Endpoint type: SUBSCRIPTION
GID: 01.0f.15.23.2d.46.9d.fb.00.00.00.00.00.02.01.04.00.00.00.00.00.00.00.00
QoS profile:
Reliability: BEST_EFFORT
History (Depth): UNKNOWN
Durability: VOLATILE
Lifespan: Infinite
Deadline: Infinite
$$
A snippet from Rviz showing the config of the PointCloud2 display: 
Now to my implementation, the node using depth_image_proc configured in my slam_nav.launch.py file:
$$
depth_to_pointcloud_node = Node(
package='depth_image_proc',
executable='point_cloud_xyz_node',
name='oak_pointcloud',
remappings=[
('image_rect', '/oak/stereo/image_raw'),
('camera_info', '/oak/stereo/camera_info'),
('points', '/oak/depth/points'),
],
parameters=[{
'use_sim_time': use_sim_time,
'queue_size': 100,
'approximate_sync': True,
'slop': 5.0,
'max_interval': 10.0,
}],
output='screen',
)
$$
The parameter file for my depth camera (highly uncertain of its correctness):
$$
/oak:
ros__parameters:
camera:
i_enable_imu: false
i_enable_ir: false
i_nn_type: none
_# Enable synchronization
sync_nn: true
sync_video_meta: true
stereo:
i_subpixel: true
_# Set consistent FPS
fps: 10 # Lower FPS for better performance and sync
_# Correct frame for stereo camera
camera_name: "stereo"
_# Enable depth output
enable_depth: true
_# Depth settings
depth:
depth_aligned: true
median_kernel_size: 3
depth_limit_mm: 10000
confidence_threshold: 200
_# TF settings
publish_tf: true
tf_publish_rate: 10.0
base_frame: "oak_stereo_camera_frame"
parent_frame: "3d_camera_link"
$$
Hope that someone can provide some insight to what I am missing for the data to be published by the /oak/depth/points topic using the depth_image_proc package.
Cheers, Hampus