Insufficient, incoherent sampling rate with ZED-ROS2 wrapper

Greetings,

I’m developing a Visual-Inertial Navigation application using the ZED-ROS2 Wrapper. However, I’m facing some serious issues when I record data using the ros2 bag record command, as follows:

  1. Insufficient camera image topic publish rate
    • ZED-ROS2 wrapper cannot publish camera images at 60fps with HD720@60fps settings. the camera topic publish rate is only around 37 Hz.
    • With ros2 bag record function, the camera publish rate drops drastically from about 37 Hz down to roughly 27 Hz.
  2. Unreliable IMU topic sampling rate
    • Although the IMU maintains a desired topic publish rate (up to 400Hz), the variance in the recorded sampling rate is exceptionally high.

None of the measures I’ve tried to improve this instability have worked:

  1. I forced best_effort QoS overrides in the common_stereo.yaml configuration (as shown below), but saw no improvement.
  2. Disabling depth and pose tracking features helps raise camera topic publish rate slightly, but does not solve the problem.
  3. Subscribing compressed / uncompressed images (.../image_raw_color or .../image_raw_color/compressed) doesn’t show any differences.

During the entire ros2 bag record process, both CPU and GPU utilization on the Jetson device remained well below capacity, and the system uses a high-speed NVMe SSD for storage. Therefore, we do not believe this issue is caused by hardware-related problems.

Despite extensive research—including browsing the Stereolabs forums and related documentation—we have not been able to find a clear solution to this problem.

I would greatly appreciate any guidance you can provide :sob:.


Hardwares & Configurations

Before sharing the recorded results, here is the hardware/software environment we used:

  • ZED SDK: 5.0 (I’ve also tried 4.x version)
  • ZED-ROS2 Wrapper: Latest main branch (2025-05-10)
  • Storage: NVMe SSD, 512 GB
  • Compute Platform:
    • NVIDIA Jetson Orin NX (16 GB RAM)
    • Jetson Orin Nano Carrier Board
    • JetPack 6.2 (CUDA 12.6, OpenCV 4.8.0)
    • ROS2 Humble, python 3.10
  • ZED Cameras
    • ZED mini, ZED2i connected via USB 3.2
    • Camera set to HD720, grab & publish @ 60 fps
    • Publish resolution: NATIVE

My goal is to stream sensor data as quickly as possible, so I modified the following settings:

  • Disabled depth sensing and positional tracking
  • Tuned sensor and camera grab & publish rate parameters
  • Applied best_effort QoS for both IMU and camera topics
# config/zedm_yaml
# Parameters for Stereolabs ZED mini camera

# 목적: depth, tracking 이런거 다 제끼고 최대한 빠르게 camera, IMU sensor data 뽑아내기
# `zed_wrapper/config/common_stereo.yaml` 의 항목을 덮어써서 사용하게 됨.
---
/**:
    ros__parameters:
        general:
            camera_model: 'zedm'
            camera_name: 'zedm' # usually overwritten by launch file
            grab_resolution: 'HD720' # The native camera grab resolution. 'HD2K', 'HD1080', 'HD720', 'VGA', 'AUTO'
            grab_frame_rate: 60 # ZED SDK internal grabbing rate
            pub_resolution: 'NATIVE' # 'NATIVE', 'CUSTOM', 'OPTIMIZED'
            pub_frame_rate: 60.0 # RGB/Depth publish rate (double)
            enable_image_validity_check: 0 # [SDK5 required] Sets the image validity check. If set to 1, the SDK will check if the frames are valid before processing.

        # Override QoS for fast-publishing data
        qos_overrides:
            '/zed/zed_node/imu/data_raw':
                publisher:
                    reliability: best_effort
            '/zed/zed_node/imu/mag':
                publisher:
                    reliability: best_effort
            '/zed/zed_node/left_raw/image_raw_color/compressed':
                publisher:
                    reliability: best_effort
            '/zed/zed_node/right_raw/image_raw_color/compressed':
                publisher:
                    reliability: best_effort

        # Maximize IMU readings
        sensors:
            sensors_pub_rate: 400. # frequency of publishing of sensors data. MAX: 400. - MIN: grab rate

        # disable depth sensing
        depth:
            depth_mode: 'NONE' # Matches the ZED SDK setting: 'NONE', 'PERFORMANCE', 'QUALITY', 'ULTRA', 'NEURAL', 'NEURAL_PLUS' - Note: if 'NONE' all the modules that requires depth extraction are disabled by default (Pos. Tracking, Obj. Detection, Mapping, ...)
            min_depth: 0.1 # Min: 0.1, Max: 3.0
            max_depth: 10.0 # Max: 20.0

        # disable pos tracking
        pos_tracking:
            pos_tracking_enabled: false # True to enable positional tracking from start
            imu_fusion: false # enable/disable IMU fusion. When set to false, only the optical odometry will be used.
            publish_tf: false # [overwritten by launch file options] publish `odom -> camera_link` TF
            publish_map_tf: false # [overwritten by launch file options] publish `map -> odom` TF

ZED cameras are connected via USB 3.2 (10Gbps), as follows:

$ sudo dmesg -w | grep ZED
[  231.526454] hid-generic 0003:2B03:F881.0003: hidraw2: USB HID v1.11 Device [STEREOLABS ZED-2i HID INTERFACE] on usb-3610000.usb-2.1.2/input0
[  231.656411] usb 2-1.1: Found UVC 1.10 device ZED 2i (2b03:f880)
[  231.679062] input: ZED 2i: ZED 2i as /devices/platform/bus@0/3610000.usb/usb2/2-1/2-1.1/2-1.1:1.0/input/input9
[  281.292108] hid-generic 0003:2B03:F881.0004: hidraw2: USB HID v1.11 Device [STEREOLABS ZED-2i HID INTERFACE] on usb-3610000.usb-2.1.2/input0

The following topics are recorded:

# sensor data
'/zed/zed_node/imu/data_raw'

# Left, Right cam
'/zed/zed_node/left_raw/image_raw_color/compressed'
'/zed/zed_node/right_raw/image_raw_color/compressed'

Issue 1: Insufficient camera image topic publish rate

When I start recording with these settings:

  • The camera frame rate (which is already limited to about 36–37 Hz at launch) drops further to ≈ 27 Hz under rosbag2 record.
  • The IMU topic still publishes at roughly 380–390 Hz with no significant variance.
  • CPU and GPU both show ample headroom throughout.

Initial launch behavior (before recording):

  • On both ZED2i and ZED mini, even though I configure HD720 @ 60 fps, the node only ever publishes at ~36–37 fps at startup.
  • I verified this in rqt, and the frame rate does not change whether or not rqt is running.

Behavior under rosbag2 record:

  • The camera topic drops from ~37 Hz down to ~27 Hz.
  • The IMU topic remains at ~380–390 Hz, with only minor fluctuations.
  • This degradation happens identically on both ZED2i and ZED mini.

Recorded timestamps from the camera image topic are shown below:


Issue 2: Unreliable IMU topic sampling rate

The timestamp variance observed in the logged IMU sensor data is significantly larger than expected. The results are visualized below:

Below is the result from recording only the IMU topic using ros2 bag record, specifically for IMU intrinsic calibration. Even without recording any image topics, the IMU sampling rate still shows unreasonably high variance.

This indicates that the issue is not caused by camera image encoding or bandwidth limitations, but rather suggests an underlying problem in how the IMU data is retrieved or published under the current configuration.

These results appear to match the “incoherent” case described in the Kalibr documentation and community discussions. Below is a reference comparison showing two inappropriate examples (left) and one correct example (right). Our case clearly falls into the incoherent category, which “bursts” the sensor data messages.

Hi @K2H
Welcome to the Stereolabs community.

What Depth mode are you using? Did you tune your system by following this section of the documentation?

ROS 2 is not real-time. It’s not possible to guarantee a precise ODR for a high frequency data.

ros bag recording is HIGH DEMANDING in terms of CPU resources and disk write speed.
If you subscribed to too many large topics and enabled data compression for both ros bag and image data, your NVIDIA Jetson Orin NX is surely overloaded.