Record and Replay camera data with ROS2
This guide provides step-by-step instructions for recording and replaying data with the ZED ROS 2 wrapper. You’ll learn how to capture camera sensor data into SVO or ROS 2 bag files, and how to replay these recordings for debugging, analysis, or development.
The guide also highlights best practices for data synchronization, playback configuration, and optimizing your workflow for efficient data handling.
⚠️ In order to use the recording and replay tools efficiently, ensure to tune your DDS settings properly by following the dedicated tutorial.
Recording and replaying SVO files #
Record SVO files with the ZED Ros Wrapper #
An SVO file is a proprietary video format used by the ZED stereo camera to record:
- Synchronized stereo video (left and right images)
- Inertial Measurement Unit (IMU) and other sensor data (temperature, magnetometer, barometer if available)
✅ Main advantages of the SVO
- Low system load during recording: Only essential sensor data is saved, resulting in smaller file sizes and minimal CPU usage. Heavy data types such as point clouds and stereo images can be generated later from the SVO during replay, reducing the need for high-performance hardware during data capture.
- Flexible SDK parameter tuning during replay: SVO files allow you to replay the same recorded sequence multiple times while adjusting ZED SDK parameters (e.g., depth mode, resolution, tracking settings). This enables efficient experimentation and optimization without the need to re-record data, streamlining the development and debugging process.
🚫 SVO Limitations
- Records and replays only ZED SDK sensor data: SVO files capture data directly from the camera (images, IMU, etc.) but do not include topics from other ROS nodes or external navigation modules. If you need to record and replay the full ROS ecosystem—including additional sensors or navigation data—use ROS bag files instead.
Single camera recording #
1️⃣ Launch the ZED ROS 2 Wrapper:
ros2 launch zed_wrapper zed_camera.launch.py camera_model:=<camera_model>
2️⃣ Start recording an SVO file: (in a new terminal)
ros2 service call /zed/zed_node/start_svo_rec zed_msgs/srv/StartSvoRec "{svo_filename: '/path/to/svo/file/file.svo2', compression_mode: <choose between 0 and 5>}"
SVO videos can be recorded using various compression modes. We provide both lossless and compressed modes to preserve image quality or reduce file size. Choose your preferred compression mode when recording an SVO with the ZED wrapper:
Compression Type | Average Size (% of RAW) | Mode |
---|---|---|
H.264 (AVCHD) | 1% | 1 |
H.264 LOSSLESS | 25% | 3 |
H.265 LOSSLESS | 25% | 4 |
H.265 (HEVC) | 1% | 0 / 2 (default) |
LOSSLESS (PNG/ZSTD) | 42% | 5 |
📌 Note: By default, the SVO file is saved as
zed.svo2
in the current directory. To change this, use thesvo_filename
parameter.Compression mode by default will be 0 if not assigned, which is the H265 LOSSY compression mode, similar to the default SVO recording tool in ZED_Explorer.
3️⃣ Stop the SVO recording:
ros2 service call /zed/zed_node/stop_svo_rec std_srvs/srv/Trigger
Recording Instructions (multi camera setup) #
For optimal multi-camera setups, refer to our multi-camera tutorial, which demonstrates how to configure up to four cameras using IPC (Intra-Process Communication) for zero-copy data transfer and maximum efficiency. With this approach, each camera node provides its own SVO recording service, allowing you to start and stop recordings independently. To record SVO files from multiple cameras at once, invoke the following command for each camera in separate terminals:
ros2 service call /zed_multi/<camera_name>/start_svo_rec zed_msgs/srv/StartSvoRec "{svo_filename: '/path/to/svo/file/file.svo2', compression_mode: <choose between 0 and 5>}"
Stopping the SVO recording then can be done with the following command for each camera:
ros2 service call /zed_multi/<camera_name>/stop_svo_rec std_srvs/srv/Trigger
Recording Performances #
To evaluate recording performance, the following metrics are based on tests performed with all optional SDK modules disabled (depth, positional tracking, and object detection) when launching the ZED wrapper. Up to four ZED X cameras were connected to a single Jetson board. For each camera configuration, the results represent the maximum achievable performance using the latest ZED SDK. All values are reported per camera for consistency and easy comparison.
Cameras | Resolution | Compression Mode | Max. SVO FPS | SVO Size |
---|---|---|---|---|
1 | HD1200 | H265 | 60 | 400 MB |
2 | HD1200 | H265 | 60 | 400 MB |
4 | HD1200 | H265 | 30 | 200 MB |
Cameras | Resolution | Compression Mode | Max. SVO FPS | SVO Size |
---|---|---|---|---|
1 | HD1200 | H265 | 60 | 400 MB |
2 | HD1200 | H265 | 30 | 200 MB |
4 | HD1200 | H265 | 30 | 200 MB |
Test Metrics
- The Maximum SVO FPS metric indicates the mean recording frame rate achieved for each individual SVO file.
- The SVO file size metric indicates the mean file size of an SVO recorded over a recording period of 1 minute.
Replaying SVO files with the ZED Ros Wrapper #
Once you have recorded an SVO file, you can use the ZED ROS 2 wrapper to replay it, simulating a live camera stream. During SVO playback, you can enable or disable SDK modules—such as depth sensing, point cloud generation, and tracking—to extract additional data or test different processing pipelines. This flexibility allows you to experiment with various parameter settings and replay the same sequence multiple times, making it easier to debug, optimize, and validate your robotics applications without needing to re-record data.
To replay an SVO file, first set your desired parameters in the ZED wrapper’s configuration YAML file. Then, launch the wrapper with the following command:
ros2 launch zed_wrapper zed_camera.launch.py camera_model:=<camera_model> svo_path:=</path/to/your/svo/file.svo2>
⚠️ At the moment, this feature is limited to single SVO replay.
To support debugging workflows involving SVO files within a robotics architecture, we provide several tools and tutorials:
svo_control_node
— A utility for precise control over SVO playback using the ZED ROS 2 wrapper. Features include pause/resume, step forward/backward, and playback speed adjustment.sync_node
— Enables synchronized playback of SVO files alongside external navigation data from a ROS 2 bag. Supports pause/resume and step-wise playback, while maintaining time alignment.SVO to ROS Bag Conversion Workflow
— A tutorial-based method to convert .svo files into standard ROS 2 bag files and merge them with navigation data from another bag, allowing unified playback and analysis.
👉 Follow the dedicated tutorial to learn how to use these tools effectively in your workflow.
Recording and replaying rosbag files #
Record rosbag files with the ZED ROS Wrapper #
Rosbag files provide a standard way to record and replay data within the ROS ecosystem. With the ZED ROS 2 Wrapper, you can capture not only camera sensor data but also any additional topics published by other nodes in your robotics stack. This makes rosbags ideal for debugging, analysis, and sharing complete system datasets. Recorded topics can be replayed and visualized using tools like RVIZ or Foxglove, enabling thorough inspection and troubleshooting of complex robotics applications.
✅ Main advantages of the Rosbag
- Record and replay the entire robotics stack, including all ROS topics published by any node in your system.
- Capture data from navigation modules, additional sensors, and both standard and custom (proprietary) ROS messages for complete dataset coverage.
- Easily share, analyze, and visualize recorded data using standard ROS tools and third-party applications.
🚫 Rosbag Limitations
- Recording large or high-frequency topics, such as images and point clouds, can quickly consume significant storage and system resources, potentially impacting performance.
- ZED parameters and processing options are set at recording time and cannot be changed during playback, limiting flexibility for post-recording optimization or experimentation.
Recording Best Practices #
To achieve optimal performance when working with ROS bags, we recommend following a set of best practices.
Use mcap
storage
#
The mcap
format allows rosbags optimization and the capability to be immediately replayed through visualization tools like Foxglove.
$ sudo apt install ros-"$ROS_DISTRO"-rosbag2-storage-mcap
Use image_transport
compression and ffmpeg
codecs
#
If you plan to record image topics, using FFmpeg with the NVENC (for desktop GPUs) or NvMpi (for Jetson boards) codecs in ROS 2 enables hardware-accelerated video encoding on NVIDIA GPUs. This offloads the computationally intensive encoding process from the CPU to the GPU, resulting in lower CPU usage and more stable system performance during recording. Leveraging GPU-based encoding helps maintain higher frame rates, reduces the risk of dropped frames, and allows for reliable rosbag recording even with multiple high-resolution video streams.
Follow the instructions here to build a version of ffmpeg that supports NVMPI:
git clone https://github.com/berndpfrommer/jetson-ffmpeg.git
cd jetson-ffmpeg && mkdir build && cd build && cmake -DCMAKE_INSTALL_PREFIX:PATH=/usr/local .. && sudo make install
sudo ldconfig && cd ../.. && git clone git://source.ffmpeg.org/ffmpeg.git -b release/7.1 --depth=1
sudo apt install libx264-dev
cd jetson-ffmpeg && ./ffpatch.sh ../ffmpeg && cd ../ffmpeg && ./configure --enable-nonfree --enable-shared --enable-nvmpi --enable-gpl --enable-libx264 --prefix=/usr/local && sudo make install
echo 'export LD_LIBRARY_PATH=/usr/local/lib:$LD_LIBRARY_PATH' >> ~/.bashrc && source ~/.bashrc
Once installed, ensure the codecs h264_nvmpi
/hevc_nvmpi
(for Jetson boards) or hevc_nvenc
(for desktop GPU) are properly listed within the available ffmepg codecs :
ffmpeg -codecs
We recommend installing the image_transport
plugins from source in your ROS workspace (remove any previously installed binary versions to avoid conflicts):
cd your_ros_ws/src/
# clone the image_transport_plugins package (use git commands to put it in the correct branch associated to your ros distro version)
git clone https://github.com/ros-perception/image_transport_plugins.git
# clone ffmpeg packages to support the codes within ROS
git clone https://github.com/ros-misc-utilities/ffmpeg_image_transport.git
git clone https://github.com/ros-misc-utilities/ffmpeg_encoder_decoder.git
# [optional] clone the foxglove_compressed_video_transport to ensure proper Foxglove streaming
git clone https://github.com/ros-misc-utilities/foxglove_compressed_video_transport.git
#export ffmpeg library
cd ..
rosdep install --from-paths src --ignore-src -r -y
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
source install/setup.bash
You should now be able to use the ffmpeg
installed codecs with the ROS wrapper. To do so, modify slightly the zed camera launcher to add the chosen codec parameters for the desired type of images. For example, if you want to enable Foxglove image transport with the ffmpeg h264_nvmpi
compression codec on the cameras rectified images topics, add these lines to the ZED wrapper node parameters :
node_parameters.append(
{
#Add any desired parameters for the zed camera node, then add the images image compression codecs parameters
.' + camera_name_val + '.left.image_rect_color.foxglove.encoding': 'h264_nvmpi',
'.' + camera_name_val + '.left.image_rect_color.foxglove.profile': 'main',
'.' + camera_name_val + '.left.image_rect_color.foxglove.preset': 'medium',
'.' + camera_name_val + '.left.image_rect_color.foxglove.gop': 10,
'.' + camera_name_val +'.left.image_rect_color.foxglove.bitrate': 4194304,
'.' + camera_name_val + '.right.image_rect_color.foxglove.encoding': 'h264_nvmpi',
'.' + camera_name_val + '.right.image_rect_color.foxglove.profile': 'main',
'.' + camera_name_val + '.right.image_rect_color.foxglove.preset': 'medium',
'.' + camera_name_val + '.right.image_rect_color.foxglove.gop': 10,
'.' + camera_name_val +'.right.image_rect_color.foxglove.bitrate': 4194304
}
)
Use the following command to explore available codec parameters and options:
ffmpeg -h encoder=<encoder_codec_name>
You can then adjust the launcher configuration to match your desired recording setup. The parameters will be used at the next launch of the cameras, after recompiling your ros workspace containing the ZED wrapper.
Use rosbag recording as a component node available with IPC [Optional] #
Starting with ROS 2 Jazzy, the ros2 bag
tool natively supports node composition. This allows you to launch the rosbag recorder as a composable node within a container, enabling efficient intra-process communication (IPC) and reducing data copying overhead.
For earlier ROS 2 distributions, you can achieve similar functionality using the rosbag2_composable_recorder community package. This package provides a component node for rosbag recording with IPC support, improving performance when recording high-bandwidth topics such as images or point clouds.
Tip: Using rosbag as a composable node with IPC is especially beneficial in multi-camera or high-throughput scenarios, as it minimizes CPU and memory usage during recording.
Recording Instructions #
1️⃣ Launch the ZED ROS 2 Wrapper: #
Single camera setup:
ros2 launch zed_wrapper zed_camera.launch.py camera_model:=<camera_model>
Multi camera setup (up to 4 cameras):
ros2 launch zed_multi_camera zed_multi_camera.launch.py cam_names:='[zed1,...,zed4]' cam_models:='[zedx,...,zedxm]' cam_serials:='[<serial_camera_1>,...,<serial_camera_4>]'
2️⃣ Record node topics as a Rosbag mcap
file
#
ros2 bag record -s mcap /topic1 /topic2 ...
Recording Performances of the ZED Cameras images with the ZED Wrapper #
To evaluate recording performance, the metrics below are based on tests conducted with no additional SDK modules enabled (depth, positional tracking, object detection modules disabled), using up to four ZED X cameras connected to a single Jetson board. For each camera configuration, the results reflect the maximum achievable performance using the latest version of the ZED SDK. One Rosbag file is recorded with all the cameras left and right images topics. The test is launched with the h264_nvmpi
codec added on each stereo camera rectified images topics with a bit_rate
of 4194304 and medium preset
.
Performance Tables #
Cameras | Resolution | Compression Mode | Max. Rosbag FPS | File Size |
---|---|---|---|---|
1 | HD1200 | h264_nvmpi | 23 | 50 MB |
1 | HD1080 | h264_nvmpi | 25 | 55 MB |
1 | SVGA | h264_nvmpi | 30 | 65 MB |
2 | HD1200 | h264_nvmpi | 19 | 85 MB |
2 | HD1080 | h264_nvmpi | 22 | 95 MB |
2 | SVGA | h264_nvmpi | 30 | 127 MB |
4 | HD1200 | h264_nvmpi | 16 | 140 MB |
4 | HD1080 | h264_nvmpi | 17 | 160 MB |
4 | SVGA | h264_nvmpi | 30 | 250 MB |
Cameras | Resolution | Compression Mode | Max. Rosbag FPS | File Size |
---|---|---|---|---|
1 | HD1200 | h264_nvmpi | 15 | 62 MB |
2 | HD1200 | h264_nvmpi | 15 | 124.5 MB |
4 | HD1200 | h264_nvmpi | 7.5 | 124.5 MB |
Test Metrics
- The Maximum Rosbag FPS metric indicates the mean recording frame rate achieved for the rosbag file.
- The rosbag file size metric indicates the mean file size of a rosbag recorded over a period of 1 minute.
💡 Tips for recording rosbags efficiently and reduce overall recording load #
- Record only the topics you need.
- On Jetson, use the
jetson_clocks.sh
script.- On Jetson, get the highest power mode possible (MAXN recommended)
- Split large bags with the
--max-bag-size
or--max-bag-duration
parameters.- Reduce the frame rate for the images and point clouds (e.g from 30 fps to 10 fps) to reduce rosbag loads.
- Reduce publishing rates of other topics when a fast publishing rate (>10 Hz) is not necessary.
- Images and point cloud sizes can be further reduced from the chosen resolution using the
pub_downscale_factor
parameter (e.g setting the parameter to 2.0 on a HD1200 resolution publishing images with a resolution of 960x608 pixels).- The
pub_frame_rate
parameter clamps the publishing rate to the chosen limit.
Replaying the recorded rosbag #
You can replay your recorded mcap
rosbag file using standard ROS 2 tools or visualize it directly in Foxglove. Foxglove natively supports the mcap
format and compressed image topics via the foxglove-compressed-image-transport
plugin, enabling efficient playback and inspection of high-bandwidth data. With Foxglove, you can pause, seek, and resume playback at any point, making it easy to analyze specific events or time ranges within your dataset.
To replay a rosbag in ROS 2, use:
ros2 bag play <your_bag_file>
For advanced playback options (such as rate control or topic remapping), refer to the ros2 bag play
documentation.