Skip to content

Commit

Permalink
Bag rewriter CLI and README
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <emerson.b.knapp@gmail.com>
  • Loading branch information
emersonknapp committed Dec 2, 2021
1 parent 7ba2e3e commit 8eedccb
Show file tree
Hide file tree
Showing 6 changed files with 177 additions and 0 deletions.
91 changes: 91 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,97 @@ Topic information: Topic: /chatter | Type: std_msgs/String | Count: 9 | Serializ
Topic: /my_chatter | Type: std_msgs/String | Count: 18 | Serialization Format: cdr
```

### Converting bags

Rosbag2 provides a tool `ros2 bag convert` (or, `rosbag2_transport::bag_rewrite` in the C++ API).
This allows the user to take one or more input bags, and write them out to one or more output bags with new settings.
This flexible feature enables the following features:
* Merge (multiple input bags, one output bag)
* Split top-level bags (one input bag, multiple output bags)
* Split internal files (by time or size - one input bag with fewer internal files, one output bag with more, smaller, internal files)
* Compress/Decompress (output bag(s) with different compression settings than the input(s))
* Serialization format conversion
* ... and more!

Here is an example command:

```
ros2 bag convert --input /path/to/bag1 --input /path/to/bag2 storage_id --output-options output_options.yaml
```

The `--input` argument may be specified any number of times, and takes 1 or 2 values.
The first value is the URI of the input bag.
If a second value is supplied, it specifies the storage implementation of the bag.
If no storage implementation is specified, rosbag2 will try to determine it automatically from the bag.

The `--output-options` argument must point to the URI of a YAML file specifying the full recording configuration for each bag to output (`StorageOptions` + `RecordOptions`).
This file must contain a top-level key `output_bags`, which contains a list of these objects.

The only required value in the output bags is `uri` and `storage_id`. All other values are options (however, if no topic selection is specified, this output bag will be empty!).

This example notes all fields that can have an effect, with a comment on the required ones.

```
output_bags
- uri: /output/bag1 # required
storage_id: sqlite3 # required
max_bagfile_size: 0
max_bagfile_duration: 0
storage_preset_profile: ""
storage_config_uri: ""
all: false
topics: []
rmw_serialization_format: "" # defaults to using the format of the input topic
regex: ""
exclude: ""
compression_mode: ""
compression_format: ""
compression_queue_size: 1
compression_threads: 0
include_hidden_topics: false
```

Example merge:

```
$ ros2 bag convert -i bag1 -i bag2 -o out.yaml
# out.yaml
output_bags:
- uri: merged_bag
storage_id: sqlite3
all: true
```

Example split:

```
$ ros2 bag convert -i bag1 -o out.yaml
# out.yaml
output_bags:
- uri: split1
storage_id: sqlite3
topics: [/topic1, /topic2]
- uri: split2
storage_id: sqlite3
topics: [/topic3]
```

Example compress:

```
$ ros2 bag convert -i bag1 -o out.yaml
# out.yaml
output_bags:
- uri: compressed
storage_id: sqlite3
all: true
compression_mode: file
compression_format: zstd
```

### Overriding QoS Profiles

When starting a recording or playback workflow, you can pass a YAML file that contains QoS profile settings for a specific topic.
Expand Down
51 changes: 51 additions & 0 deletions ros2bag/ros2bag/verb/convert.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
# Copyright 2021 Amazon.com Inc or its Affiliates
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import argparse

from ros2bag.verb import VerbExtension
from rosbag2_py import bag_rewrite
from rosbag2_py import StorageOptions


class ConvertVerb(VerbExtension):
"""Given an input bag, write out a new bag with different settings."""

def add_arguments(self, parser, cli_name):
parser.add_argument(
'-i', '--input',
required=True,
action='append', nargs='+',
metavar=('uri', 'storage_id'),
help='URI (and optional storage ID) of an input bag. May be provided more than once')
parser.add_argument(
'-o', '--output-options',
type=str, required=True,
help='YAML file with options for output bags. Should have one top-level key '
'"output_bags", which contains a sequence of StorageOptions/RecordOptions '
'combined objects. See README.md for some examples.')

def main(self, *, args):
input_options = []
for input_bag in args.input:
if len(input_bag) > 2:
raise argparse.ArgumentTypeError(
f'--input expects 1 or 2 arguments, {len(input_bag)} provided')
storage_options = StorageOptions()
storage_options.uri = input_bag[0]
if len(input_bag) > 1:
storage_options.storage_id = input_bag[1]
input_options.append(storage_options)

bag_rewrite(input_options, args.output_options)
1 change: 1 addition & 0 deletions ros2bag/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
'ros2bag.verb = ros2bag.verb:VerbExtension',
],
'ros2bag.verb': [
'convert = ros2bag.verb.convert:ConvertVerb',
'info = ros2bag.verb.info:InfoVerb',
'list = ros2bag.verb.list:ListVerb',
'play = ros2bag.verb.play:PlayVerb',
Expand Down
2 changes: 2 additions & 0 deletions rosbag2_py/rosbag2_py/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
Info,
)
from rosbag2_py._transport import (
bag_rewrite,
Player,
PlayOptions,
Recorder,
Expand All @@ -52,6 +53,7 @@
)

__all__ = [
'bag_rewrite',
'ConverterOptions',
'get_registered_readers',
'get_registered_writers',
Expand Down
1 change: 1 addition & 0 deletions rosbag2_py/src/rosbag2_py/_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ PYBIND11_MODULE(_storage, m) {
&rosbag2_cpp::ConverterOptions::output_serialization_format);

pybind11::class_<rosbag2_storage::StorageOptions>(m, "StorageOptions")
.def(pybind11::init<>())
.def(
pybind11::init<
std::string, std::string, uint64_t, uint64_t, uint64_t, std::string, std::string, bool>(),
Expand Down
31 changes: 31 additions & 0 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
#include <vector>

#include "rosbag2_storage/storage_options.hpp"
#include "rosbag2_storage/yaml.hpp"
#include "rosbag2_transport/bag_rewrite.hpp"
#include "rosbag2_transport/play_options.hpp"
#include "rosbag2_transport/player.hpp"
#include "rosbag2_transport/reader_writer_factory.hpp"
Expand Down Expand Up @@ -175,6 +177,30 @@ class Recorder
}
};

// Simple wrapper to read the output config YAML into structs
void bag_rewrite(
const std::vector<rosbag2_storage::StorageOptions> & input_options,
std::string output_config_file)
{
YAML::Node yaml_file = YAML::LoadFile(output_config_file);
auto bag_nodes = yaml_file["output_bags"];
if (!bag_nodes) {
throw std::runtime_error("Output bag config YAML file must have top-level key 'output_bags'");
}
if (!bag_nodes.IsSequence()) {
throw std::runtime_error("Top-level key 'output_bags' must contain a list.");
}

std::vector<
std::pair<rosbag2_storage::StorageOptions, rosbag2_transport::RecordOptions>> output_options;
for (const auto & bag_node : bag_nodes) {
auto storage_options = bag_node.as<rosbag2_storage::StorageOptions>();
auto record_options = bag_node.as<rosbag2_transport::RecordOptions>();
output_options.push_back(std::make_pair(storage_options, record_options));
}
rosbag2_transport::bag_rewrite(input_options, output_options);
}

} // namespace rosbag2_py

PYBIND11_MODULE(_transport, m) {
Expand Down Expand Up @@ -240,4 +266,9 @@ PYBIND11_MODULE(_transport, m) {
.def("record", &rosbag2_py::Recorder::record)
.def("cancel", &rosbag2_py::Recorder::cancel)
;

m.def(
"bag_rewrite",
&rosbag2_py::bag_rewrite,
"Given one or more input bags, output one or more bags with new settings.");
}

0 comments on commit 8eedccb

Please sign in to comment.