Overview

Converting ROS bags in ROS 2 is a bit unintuitive, so here’s some info. The most important starting point:

  • Everything regarding configuration and output is specified in a yaml configuration file.
  • Everything regarding the input (filename(s) of the input bag(s)) is specified on the commandline.

All the interesting stuff happens in the configuration file. There are some examples in the rosbag2 README, but that may be out of date. The config file contains both StorageOptions (parsing here) and RecordOptions (parsing here). The config file should contain one entry output_bags, which is, as expected, a sequence of configurations for each output ROS bag. Each output bag configuration contains key-value pairs for record- or storage options. The uri parameter (of StorageOptions) sets the name of the output bag.

Important Parameters

The most important parameters are:

  • uri: The name of the output bag
  • all_topics: Set to true to keep all topics in the bag. If no topic selection argument is set, the output will contain no data at all!

Examples

In the following, some examples of config files which may be useful. If not otherwise specified, the input bag is this one:

jonas@ade ➜  ~ ros2 bag info bag_jazzy_full

Files:             bag_jazzy_full_0.mcap
Bag size:          6.8 KiB
Storage id:        mcap
ROS Distro:        jazzy
Duration:          24.999s
Start:             May 17 2024 19:16:57.716 (1715966217.716)
End:               May 17 2024 19:17:22.716 (1715966242.716)
Messages:          26
Topic information: Topic: /chatter | Type: std_msgs/msg/String | Count: 26 | Serialization Format: cdr
Service:           0
Service information:

It contains messages on only one topic with a frequency of 1Hz.

Truncate Bag by Time

Create a bag containing only the first five seconds of the input bag:

output_bags:
- uri: out_truncated
  all_topics: true
  # This is optional, the default of -1 just means "from the start of the bag"
  start_time_ns: -1
  # I got this number from the "Start" field in "ros2 bag info ...", added 5s to it,
  # and converted from seconds to nanoseconds (multiply by 1000000000).
  # I also rounded the number up a bit to get the last message, maybe the message is
  # published a bit late and "ros2 bag info..." does some rounding.
  end_time_ns: 1715966222800000000
jonas@ade ➜  ~ ros2 bag convert -i bag_jazzy_full -o out_truncate.yaml
jonas@ade ➜  ~ ros2 bag info out_truncated

Files:             out_truncated_0.mcap
Bag size:          5.1 KiB
Storage id:        mcap
ROS Distro:        jazzy
Duration:          4.999s
Start:             May 17 2024 19:16:57.716 (1715966217.716)
End:               May 17 2024 19:17:02.716 (1715966222.716)
Messages:          6
Topic information: Topic: /chatter | Type: std_msgs/msg/String | Count: 6 | Serialization Format: cdr
Service:           0
Service information:

Split Bag by Time

Similar to the previous example, but instead of discarding the messages after the cutoff time, write them to a second bag. Note that if the bag contained any topics with transient_local durability that are only published once before recording started, those messages would only end up in the first output bag.

output_bags:
- uri: out_1
  all_topics: true
  start_time_ns: -1
  end_time_ns: 1715966222800000000
- uri: out_2
  all_topics: true
  start_time_ns: 1715966222800000000
  end_time_ns: -1
jonas@ade ➜  ~ ros2 bag convert -i bag_jazzy_full -o out_split.yaml
jonas@ade ➜  ~ ros2 bag info out_1 

Files:             out_1_0.mcap
Bag size:          5.1 KiB
Storage id:        mcap
ROS Distro:        jazzy
Duration:          4.999s
Start:             May 17 2024 19:16:57.716 (1715966217.716)
End:               May 17 2024 19:17:02.716 (1715966222.716)
Messages:          6
Topic information: Topic: /chatter | Type: std_msgs/msg/String | Count: 6 | Serialization Format: cdr
Service:           0
Service information: 
jonas@ade ➜  ~ ros2 bag info out_2

Files:             out_2_0.mcap
Bag size:          6.0 KiB
Storage id:        mcap
ROS Distro:        jazzy
Duration:          18.999s
Start:             May 17 2024 19:17:03.716 (1715966223.716)
End:               May 17 2024 19:17:22.716 (1715966242.716)
Messages:          20
Topic information: Topic: /chatter | Type: std_msgs/msg/String | Count: 20 | Serialization Format: cdr
Service:           0
Service information: 

Extract Specific Topic

This does not use all_topics: true, but uses the topic parameter to explicitly select topics by name. There are also options available to select topics by type, regex, or by explicitly excluding instead of including topics.

Here, the input contains two instead of one topics:

jonas@ade ➜  ~ ros2 bag info two_topics 

Files:             two_topics_0.mcap
Bag size:          9.7 KiB
Storage id:        mcap
ROS Distro:        jazzy
Duration:          16.411s
Start:             May 20 2024 13:47:16.112 (1716205636.112)
End:               May 20 2024 13:47:32.524 (1716205652.524)
Messages:          34
Topic information: Topic: /chatter1 | Type: std_msgs/msg/String | Count: 17 | Serialization Format: cdr
                   Topic: /chatter2 | Type: std_msgs/msg/String | Count: 17 | Serialization Format: cdr
Service:           0
Service information:
output_bags:
- uri: chatter1_only
  topics: ["/chatter1"]
jonas@ade ➜  ~ ros2 bag info two_topics 

Files:             two_topics_0.mcap
Bag size:          9.7 KiB
Storage id:        mcap
ROS Distro:        jazzy
Duration:          16.411s
Start:             May 20 2024 13:47:16.112 (1716205636.112)
End:               May 20 2024 13:47:32.524 (1716205652.524)
Messages:          34
Topic information: Topic: /chatter1 | Type: std_msgs/msg/String | Count: 17 | Serialization Format: cdr
                   Topic: /chatter2 | Type: std_msgs/msg/String | Count: 17 | Serialization Format: cdr
Service:           0
Service information: 
jonas@ade ➜  ~ ros2 bag convert -i two_topics -o out_extract.yaml 
jonas@ade ➜  ~ ros2 bag info chatter1_only 

Files:             chatter1_only_0.mcap
Bag size:          5.9 KiB
Storage id:        mcap
ROS Distro:        jazzy
Duration:          16.0s
Start:             May 20 2024 13:47:16.524 (1716205636.524)
End:               May 20 2024 13:47:32.524 (1716205652.524)
Messages:          17
Topic information: Topic: /chatter1 | Type: std_msgs/msg/String | Count: 17 | Serialization Format: cdr
Service:           0
Service information: