* This blog post is an English translation of an article originally published in Japanese on January 23, 2023.
Introduction
With https://github.com/ros2/rosbag2/pull/1163, the rosbag2_storage_mcap
package was added, allowing MCAP to be selected as the storage format for rosbag2. This article introduces how to use rosbag2_storage_mcap.
Test Environment
The environment used for operational verification is as follows:
- Ubuntu 22.04
- ROS2 Humble
- rosbag2_storage_mcap 0.6.0
What is MCAP?
MCAP (https://mcap.dev/index.html) is a data format for recording various types of timestamped data. It allows multiple streams of structured and unstructured data (e.g., ROS2, Protobuf, JSON Schema) to be recorded in a single file. For details on the MCAP file format, please refer to https://mcap.dev/specification/index.html. Furthermore, it has been announced at https://foxglove.dev/blog/mcap-as-the-ros2-default-bag-format that MCAP is planned to become the default storage for rosbag2 starting from ROS 2 Iron Irwini.
Benefits of MCAP
The benefits of MCAP, extracted from the “Benefits” section of https://mcap.dev/index.html, are listed below:
- Good write performance
- Easy recovery if data is corrupted during recording
- Data can be extracted without scanning the entire file
- No extra package dependencies for decoding
rosbag2_storage_mcap Installation
Execute the following command to install the rosbag2_storage_mcap
package.
$ sudo apt install ros-humble-rosbag2-storage-mcap
Recording rosbag2 in MCAP Format
Execute the following command to save all topics in MCAP format. The -s
option specifies the storage type. For detailed options, please check ros2 bag -h
.
$ ros2 bag record -s mcap --all
Comparison of rosbag2 File Sizes (SQLite3 vs MCAP)
For rosbag2_storage_mcap
, as described in https://github.com/ros2/rosbag2/blob/humble/rosbag2_storage_mcap/README.md#writer-configuration, the following can be specified for compression:
- compression
- Can specify None, Lz4, or Zstd.
- compressionLevel
- Can specify Fastest, Fast, Default, Slow, or Slowest.
Here, we checked the rosbag2 file sizes under the following conditions:
- SQLite3 (ROS2 Humble default): No compression
- SQLite3 (ROS2 Humble default): Zstd compression
- MCAP: Zstd(fast)
- MCAP: Zstd(default)
- MCAP: Zstd(slow)
- MCAP: Lz4(fast)
The file sizes of rosbag2 generated under each condition are shown in the table below. However, the MCAP+Lz4(default)
and MCAP+Lz4(slow)
cases were excluded from measurement because an error occurred when saving the rosbag2 file.
RGB-D Data
The results when using RGB-D data (see Appendix for details) are shown in the table below. It can be seen that MCAP+Zstd(slow) results in a file size comparable to SQLite3+Zstd.
storage type | compression | size(MB) |
SQLite3 | No compression | 1359 |
SQLite3 | Zstd | 408 |
MCAP | Zstd(fast) | 500 |
MCAP | Zstd(default) | 472 |
MCAP | Zstd(slow) | 393 |
MCAP | Lz4(fast) | 633 |
Autoware sample rosbag2
The results when using the Autoware sample rosbag2 (see Appendix for details) are shown in the table below. It can be seen that MCAP+Zstd(slow) results in a file size comparable to SQLite3+Zstd.
storage type | compression | size(GB) |
SQLite3 | No compression | 7.9 |
SQLite3 | Zstd | 2.8 |
MCAP | Zstd(fast) | 3.1 |
MCAP | Zstd(default) | 2.7 |
MCAP | Zstd(slow) | 2.8 |
MCAP | Lz4(fast) | 3.6 |
MCAP CLI Tools
We introduce CLI tools for handling MCAP. Download from https://github.com/foxglove/mcap/blob/releases/cpp/v0.6.0/go/cli/mcap/README.md. The execution options are as follows:
Usage:
mcap [command]
Available Commands:
add Add records to an existing MCAP file
cat Cat the messages in an MCAP file to stdout
completion Generate the autocompletion script for the specified shell
compress Compress data in an MCAP file
convert Convert a bag file to an MCAP file
doctor Check an MCAP file structure
filter Copy some filtered MCAP data to a new file
get Get a record from an MCAP file
help Help about any command
info Report statistics about an MCAP file
list List records of an MCAP file
merge Merge a selection of MCAP files by record timestamp
recover Recover data from a potentially corrupt MCAP file
version Output version information
Flags:
--config string Config file (default is $HOME/.mcap.yaml)
-h, --help help for mcap
Use "mcap [command] --help" for more information about a command.
Here, we will introduce the following commands:
- info
- cat
- doctor
info command
Displays a summary of the information recorded in the MCAP file. An execution example is as follows:
$ mcap info zstd_default_0.mcap
library: libmcap 0.7.0
profile: ros2
messages: 5326
duration: 47.452457991s
start: 2023-01-05T16:28:57.516754852+09:00 (1672903737.516754852)
end: 2023-01-05T16:29:44.969212843+09:00 (1672903784.969212843)
compression:
zstd: [1194/1194 chunks] [1356 MB/470 MB (65.29%)] [9.90 MB/sec]
channels:
(1) /rosout 35 msgs (0.74 Hz) : rcl_interfaces/msg/Log [ros2msg]
(2) /events/write_split 0 msgs (0.00 Hz) : rosbag2_interfaces/msg/WriteSplitEvent [ros2msg]
(3) /events/read_split 0 msgs (0.00 Hz) : rosbag2_interfaces/msg/ReadSplitEvent [ros2msg]
(4) /parameter_events 0 msgs (0.00 Hz) : rcl_interfaces/msg/ParameterEvent [ros2msg]
(5) /camera/depth/image_rect_raw 661 msgs (13.93 Hz) : sensor_msgs/msg/Image [ros2msg]
(6) /camera/aligned_depth_to_color/camera_info 661 msgs (13.93 Hz) : sensor_msgs/msg/CameraInfo [ros2msg]
(7) /camera/depth/metadata 661 msgs (13.93 Hz) : realsense2_camera_msgs/msg/Metadata [ros2msg]
(8) /camera/extrinsics/depth_to_depth 1 msgs (0.02 Hz) : realsense2_camera_msgs/msg/Extrinsics [ros2msg]
(9) /camera/aligned_depth_to_color/image_raw 661 msgs (13.93 Hz) : sensor_msgs/msg/Image [ros2msg]
(10) /camera/color/camera_info 661 msgs (13.93 Hz) : sensor_msgs/msg/CameraInfo [ros2msg]
(11) /camera/color/image_raw 661 msgs (13.93 Hz) : sensor_msgs/msg/Image [ros2msg]
(12) /camera/color/metadata 661 msgs (13.93 Hz) : realsense2_camera_msgs/msg/Metadata [ros2msg]
(13) /camera/depth/camera_info 661 msgs (13.93 Hz) : sensor_msgs/msg/CameraInfo [ros2msg]
(14) /tf_static 1 msgs (0.02 Hz) : tf2_msgs/msg/TFMessage [ros2msg]
(15) /camera/extrinsics/depth_to_color 1 msgs (0.02 Hz) : realsense2_camera_msgs/msg/Extrinsics [ros2msg]
(16) /camera/imu 0 msgs (0.00 Hz) : sensor_msgs/msg/Imu [ros2msg]
attachments: 0
metadata: 0
cat command
Displays a summary of the recorded topic contents to standard output. An execution example is as follows:
$ mcap cat zstd_default_0.mcap
1672903737516754852 /rosout [rcl_interfaces/msg/Log] [0 1 0 0 57 124 182 99 88 237]...
1672903737516870652 /rosout [rcl_interfaces/msg/Log] [0 1 0 0 57 124 182 99 108 241]...
≪Omitted≫
1672903741204468335 /camera/aligned_depth_to_color/camera_info [sensor_msgs/msg/CameraInfo] [0 1 0 0 61 109 182 99 0 8]...
1672903741204537835 /camera/depth/metadata [realsense2_camera_msgs/msg/Metadata] [0 1 0 0 61 109 182 99 0 8]...
1672903741204545735 /tf_static [tf2_msgs/msg/TFMessage] [0 1 0 0 4 0 0 0 28 109]...
1672903741204576835 /camera/extrinsics/depth_to_color [realsense2_camera_msgs/msg/Extrinsics] [0 1 0 0 0 0 0 192 247 255]...
≪Omitted≫
doctor command
Checks if the rosbag2 file is corrupted. An execution example is as follows. The data used this time was not corrupted, so no error messages were displayed.
$ mcap doctor zstd_default_0.mcap
Examining zstd_default_0.mcap
Caveats
As of this writing, rqt_bag does not seem to support MCAP, and attempting to open a rosbag2 (MCAP) file with rqt_bag results in the following error message:
sqlite3.DatabaseError: file is not a database
Measures have been taken for Rolling, so it may be backported to Humble in the future.
- https://github.com/ros-visualization/rqt_bag/pull/126
- https://github.com/ros-visualization/rqt_bag/issues/121
Warning message: ‘No storage plugin found with id mcap’
This has been reported at https://github.com/ros2/rosbag2/issues/1195. This message has been removed for Rolling, but it seems that how to address it for Humble is under consideration.
Future Plans
- Benchmarking
- Run benchmarks with reference to https://mcap.dev/performance-comparison/rosbag2-plugin-comparison.html
- MCAP API
- Read and write MCAP from Python, C++, etc.
- Visualization of MCAP data
Appendix
Input rosbag2 files used for file size verification
The input rosbag2 files (SQLite3, uncompressed) used for file size verification are as follows.
RGB-D Data
$ ros2 bag info rosbag2_2023_01_05-15_25_01/
Files: rosbag2_2023_01_05-15_25_01_0.db3
Bag size: 1.3 GiB
Storage id: sqlite3
Duration: 44.66s
Start: Jan 5 2023 15:25:01.719 (1672899901.719)
End: Jan 5 2023 15:25:45.786 (1672899945.786)
Messages: 5301
Topic information: Topic: /events/write_split | Type: rosbag2_interfaces/msg/WriteSplitEvent | Count: 0 | Serialization Format: cdr
Topic: /camera/imu | Type: sensor_msgs/msg/Imu | Count: 0 | Serialization Format: cdr
Topic: /camera/aligned_depth_to_color/camera_info | Type: sensor_msgs/msg/CameraInfo | Count: 661 | Serialization Format: cdr
Topic: /camera/depth/metadata | Type: realsense2_camera_msgs/msg/Metadata | Count: 661 | Serialization Format: cdr
Topic: /camera/extrinsics/depth_to_depth | Type: realsense2_camera_msgs/msg/Extrinsics | Count: 1 | Serialization Format: cdr
Topic: /camera/aligned_depth_to_color/image_raw | Type: sensor_msgs/msg/Image | Count: 661 | Serialization Format: cdr
Topic: /camera/color/camera_info | Type: sensor_msgs/msg/CameraInfo | Count: 661 | Serialization Format: cdr
Topic: /camera/color/image_raw | Type: sensor_msgs/msg/Image | Count: 661 | Serialization Format: cdr
Topic: /rosout | Type: rcl_interfaces/msg/Log | Count: 10 | Serialization Format: cdr
Topic: /camera/color/metadata | Type: realsense2_camera_msgs/msg/Metadata | Count: 661 | Serialization Format: cdr
Topic: /camera/depth/camera_info | Type: sensor_msgs/msg/CameraInfo | Count: 661 | Serialization Format: cdr
Topic: /camera/depth/image_rect_raw | Type: sensor_msgs/msg/Image | Count: 661 | Serialization Format: cdr
Topic: /parameter_events | Type: rcl_interfaces/msg/ParameterEvent | Count: 0 | Serialization Format: cdr
Topic: /tf_static | Type: tf2_msgs/msg/TFMessage | Count: 1 | Serialization Format: cdr
Autoware sample rosbag2
Used sample_moriyama_150324.bag2 from https://gitlab.com/autowarefoundation/autoware.ai/autoware/-/wikis/ROSBAG-Demo.
$ ros2 bag info sample_moriyama_150324.bag2/
Files: sample_moriyama_150324.bag2/sample_moriyama_150324.bag2_0.db3
Bag size: 7.9 GiB
Storage id: sqlite3
Duration: 479.172s
Start: Feb 21 2020 02:04:31.772 (1582218271.772)
End: Feb 21 2020 02:12:30.944 (1582218750.944)
Messages: 16768
Topic information: Topic: /clock | Type: rosgraph_msgs/msg/Clock | Count: 0 | Serialization Format: cdr
Topic: /nmea_sentence | Type: nmea_msgs/msg/Sentence | Count: 11980 | Serialization Format: cdr
Topic: /points_raw | Type: sensor_msgs/msg/PointCloud2 | Count: 4788 | Serialization Format: cdr
Reference URLs
- https://github.com/ros2/rosbag2/pull/1160
- PR to make MCAP the default storage in Rolling
- https://vimeo.com/showcase/9954564/video/767149733
- ROSCon 2022 video
- http://download.ros.org/downloads/roscon/2022/MCAP%20A%20Next-Generation%20File%20Format%20for%20ROS%20Recording.pdf
- ROSCon 2022 slides
- https://foxglove.dev/blog/announcing-the-mcap-storage-plugin-for-ros2
- Blog post about rosbag2_storage_mcap
- https://foxglove.dev/blog/mcap-as-the-ros2-default-bag-format
- Announcement that MCAP will be the default storage for rosbag2 from ROS 2 Iron Irwini
- https://foxglove.dev/blog/plotjuggler-adds-support-for-mcap
- Blog post about PlotJuggler adding MCAP support
- https://mcap.dev/performance-comparison/rosbag2-plugin-comparison.html
- Benchmark results