Add conversion from rosbag2 to rosbag1

This commit is contained in:
Marko Durkovic 2022-01-09 20:31:51 +01:00
parent ac55fd2f4a
commit 2eb3b1c671
6 changed files with 269 additions and 42 deletions

View File

@ -46,14 +46,20 @@ Read and deserialize rosbag2 messages:
print(msg.header.frame_id)
Convert rosbag1 to rosbag2::
Convert between rosbag versions::
# Convert "foo.bag", result will be "foo/"
rosbags-convert foo.bag
# Convert "bar", result will be "bar.bag"
rosbags-convert bar
# Convert "foo.bag", save the result as "bar"
rosbags-convert foo.bag --dst /path/to/bar
# Convert "bar", save the result as "foo.bag"
rosbags-convert bar --dst /path/to/foo.bag
Documentation
=============

View File

@ -1,7 +1,7 @@
Convert Rosbag1 to Rosbag2
==========================
The :py:mod:`rosbags.convert` package includes a CLI tool to convert legacy rosbag1 files to rosbag2.
The :py:mod:`rosbags.convert` package includes a CLI tool to convert legacy rosbag1 files to rosbag2 and vice versa.
Features
--------
@ -14,8 +14,9 @@ Features
Limitations
-----------
- Refuses to convert unindexed rosbag files, please reindex files before conversion
- Refuses to convert unindexed rosbag1 files, please reindex files before conversion
- Currently does not handle split bags
- Only ROS2 default message types are supported when converting rosbag2 to rosbag1
Usage
-----
@ -25,5 +26,11 @@ Usage
# Convert "foo.bag", result will be "foo/"
$ rosbags-convert foo.bag
# Convert "bar", result will be "bar.bag"
$ rosbags-convert bar
# Convert "foo.bag", save the result as "bar"
$ rosbags-convert foo.bag --dst /path/to/bar
# Convert "bar", save the result as "foo.bag"
$ rosbags-convert bar --dst /path/to/foo.bag

View File

@ -39,18 +39,23 @@ def pathtype(exists: bool = True) -> Callable[[str], Path]:
def main() -> None:
"""Parse cli arguments and run conversion."""
parser = argparse.ArgumentParser(description='Convert rosbag1 to rosbag2.')
parser = argparse.ArgumentParser(description='Convert between rosbag1 and rosbag2.')
parser.add_argument(
'src',
type=pathtype(),
help='source path to read rosbag1 from',
help='source path to read rosbag1 or rosbag2 from',
)
parser.add_argument(
'--dst',
type=pathtype(exists=False),
help='destination path for rosbag2',
help='destination path for converted rosbag',
)
args = parser.parse_args()
if args.dst is not None and (args.src.suffix == '.bag') == (args.dst.suffix == '.bag'):
print('Source and destination rosbag versions must differ.') # noqa: T001
sys.exit(1)
try:
convert(args.src, args.dst)
except ConverterError as err:

View File

@ -7,18 +7,24 @@ from __future__ import annotations
from dataclasses import asdict
from typing import TYPE_CHECKING
from rosbags.rosbag1 import Reader, ReaderError
from rosbags.rosbag2 import Writer, WriterError
from rosbags.rosbag2.connection import Connection as WConnection
from rosbags.serde import ros1_to_cdr
from rosbags.rosbag1 import Reader as Reader1
from rosbags.rosbag1 import ReaderError as ReaderError1
from rosbags.rosbag1 import Writer as Writer1
from rosbags.rosbag1 import WriterError as WriterError1
from rosbags.rosbag1.reader import Connection as Connection1
from rosbags.rosbag2 import Reader as Reader2
from rosbags.rosbag2 import ReaderError as ReaderError2
from rosbags.rosbag2 import Writer as Writer2
from rosbags.rosbag2 import WriterError as WriterError2
from rosbags.rosbag2.connection import Connection as Connection2
from rosbags.serde import cdr_to_ros1, ros1_to_cdr
from rosbags.typesys import get_types_from_msg, register_types
from rosbags.typesys.msg import generate_msgdef
if TYPE_CHECKING:
from pathlib import Path
from typing import Any, Optional
from rosbags.rosbag1.reader import Connection as RConnection
LATCH = """
- history: 3
depth: 0
@ -42,7 +48,7 @@ class ConverterError(Exception):
"""Converter Error."""
def convert_connection(rconn: RConnection) -> WConnection:
def upgrade_connection(rconn: Connection1) -> Connection2:
"""Convert rosbag1 connection to rosbag2 connection.
Args:
@ -52,7 +58,7 @@ def convert_connection(rconn: RConnection) -> WConnection:
Rosbag2 connection.
"""
return WConnection(
return Connection2(
-1,
0,
rconn.topic,
@ -62,41 +68,108 @@ def convert_connection(rconn: RConnection) -> WConnection:
)
def convert(src: Path, dst: Optional[Path]) -> None:
def downgrade_connection(rconn: Connection2) -> Connection1:
"""Convert rosbag2 connection to rosbag1 connection.
Args:
rconn: Rosbag2 connection.
Returns:
Rosbag1 connection.
"""
msgdef, md5sum = generate_msgdef(rconn.msgtype)
return Connection1(
-1,
rconn.topic,
rconn.msgtype,
msgdef,
md5sum,
None,
int('durability: 1' in rconn.offered_qos_profiles),
[],
)
def convert_1to2(src: Path, dst: Path) -> None:
"""Convert Rosbag1 to Rosbag2.
Args:
src: Rosbag1 path.
dst: Rosbag2 path.
"""
with Reader1(src) as reader, Writer2(dst) as writer:
typs: dict[str, Any] = {}
connmap: dict[int, Connection2] = {}
for rconn in reader.connections.values():
candidate = upgrade_connection(rconn)
existing = next((x for x in writer.connections.values() if x == candidate), None)
wconn = existing if existing else writer.add_connection(**asdict(candidate))
connmap[rconn.cid] = wconn
typs.update(get_types_from_msg(rconn.msgdef, rconn.msgtype))
register_types(typs)
for rconn, timestamp, data in reader.messages():
data = ros1_to_cdr(data, rconn.msgtype)
writer.write(connmap[rconn.cid], timestamp, data)
def convert_2to1(src: Path, dst: Path) -> None:
"""Convert Rosbag2 to Rosbag1.
Args:
src: Rosbag2 path.
dst: Rosbag1 path.
"""
with Reader2(src) as reader, Writer1(dst) as writer:
connmap: dict[int, Connection1] = {}
for rconn in reader.connections.values():
candidate = downgrade_connection(rconn)
# yapf: disable
existing = next(
(
x
for x in writer.connections.values()
if x.topic == candidate.topic
if x.md5sum == candidate.md5sum
if x.latching == candidate.latching
),
None,
)
# yapf: enable
connmap[rconn.id] = existing if existing else writer.add_connection(*candidate[1:-1])
for rconn, timestamp, data in reader.messages():
data = cdr_to_ros1(data, rconn.msgtype)
writer.write(connmap[rconn.id], timestamp, data)
def convert(src: Path, dst: Optional[Path]) -> None:
"""Convert between Rosbag1 and Rosbag2.
Args:
src: Source rosbag.
dst: Destination rosbag.
Raises:
ConverterError: An error occured during reading, writing, or
converting.
"""
dst = dst if dst else src.with_suffix('')
upgrade = src.suffix == '.bag'
dst = dst if dst else src.with_suffix('' if upgrade else '.bag')
if dst.exists():
raise ConverterError(f'Output path {str(dst)!r} exists already.')
func = convert_1to2 if upgrade else convert_2to1
try:
with Reader(src) as reader, Writer(dst) as writer:
typs: dict[str, Any] = {}
connmap: dict[int, WConnection] = {}
for rconn in reader.connections.values():
candidate = convert_connection(rconn)
existing = next((x for x in writer.connections.values() if x == candidate), None)
wconn = existing if existing else writer.add_connection(**asdict(candidate))
connmap[rconn.cid] = wconn
typs.update(get_types_from_msg(rconn.msgdef, rconn.msgtype))
register_types(typs)
for rconn, timestamp, data in reader.messages():
data = ros1_to_cdr(data, rconn.msgtype)
writer.write(connmap[rconn.cid], timestamp, data)
except ReaderError as err:
func(src, dst)
except (ReaderError1, ReaderError2) as err:
raise ConverterError(f'Reading source bag: {err}') from err
except WriterError as err:
except (WriterError1, WriterError2) as err:
raise ConverterError(f'Writing destination bag: {err}') from err
except Exception as err: # pylint: disable=broad-except
raise ConverterError(f'Converting rosbag: {err!r}') from err

View File

@ -126,7 +126,7 @@ def cdr_to_ros1(raw: bytes, typename: str) -> memoryview:
None,
0,
)
assert ipos + 4 == len(raw)
assert ipos + 4 + 3 >= len(raw)
raw = memoryview(raw)
size = opos
@ -138,6 +138,6 @@ def cdr_to_ros1(raw: bytes, typename: str) -> memoryview:
rawdata,
0,
)
assert ipos + 4 == len(raw)
assert ipos + 4 + 3 >= len(raw)
assert opos == size
return rawdata.toreadonly()

View File

@ -46,6 +46,15 @@ def test_cliwrapper(tmp_path: Path) -> None:
main()
assert not cvrt.called
with patch('rosbags.convert.__main__.convert') as cvrt, \
patch.object(sys, 'argv', ['cvt',
str(tmp_path / 'ros1.bag'),
'--dst',
str(tmp_path / 'ros2.bag')]), \
pytest.raises(SystemExit):
main()
assert not cvrt.called
with patch('rosbags.convert.__main__.convert') as cvrt, \
patch.object(sys, 'argv', ['cvt',
str(tmp_path / 'ros1.bag'),
@ -61,17 +70,46 @@ def test_cliwrapper(tmp_path: Path) -> None:
main()
mock_print.assert_called_with('ERROR: exc')
with patch('rosbags.convert.__main__.convert') as cvrt, \
patch.object(sys, 'argv', ['cvt', str(tmp_path / 'subdir')]):
main()
cvrt.assert_called_with(tmp_path / 'subdir', None)
def test_convert(tmp_path: Path) -> None:
"""Test conversion function."""
with patch('rosbags.convert.__main__.convert') as cvrt, \
patch.object(sys, 'argv', ['cvt',
str(tmp_path / 'subdir'),
'--dst',
str(tmp_path / 'ros1.bag')]), \
pytest.raises(SystemExit):
main()
assert not cvrt.called
with patch('rosbags.convert.__main__.convert') as cvrt, \
patch.object(sys, 'argv', ['cvt',
str(tmp_path / 'subdir'),
'--dst',
str(tmp_path / 'target.bag')]):
main()
cvrt.assert_called_with(tmp_path / 'subdir', tmp_path / 'target.bag')
with patch.object(sys, 'argv', ['cvt', str(tmp_path / 'subdir')]), \
patch('builtins.print') as mock_print, \
patch('rosbags.convert.__main__.convert', side_effect=ConverterError('exc')), \
pytest.raises(SystemExit):
main()
mock_print.assert_called_with('ERROR: exc')
def test_convert_1to2(tmp_path: Path) -> None:
"""Test conversion from rosbag1 to rosbag2."""
(tmp_path / 'subdir').mkdir()
(tmp_path / 'foo.bag').write_text('')
with pytest.raises(ConverterError, match='exists already'):
convert(Path('foo.bag'), tmp_path / 'subdir')
with patch('rosbags.convert.converter.Reader') as reader, \
patch('rosbags.convert.converter.Writer') as writer, \
with patch('rosbags.convert.converter.Reader1') as reader, \
patch('rosbags.convert.converter.Writer2') as writer, \
patch('rosbags.convert.converter.get_types_from_msg', return_value={'typ': 'def'}), \
patch('rosbags.convert.converter.register_types') as register_types, \
patch('rosbags.convert.converter.ros1_to_cdr') as ros1_to_cdr:
@ -137,14 +175,112 @@ def test_convert(tmp_path: Path) -> None:
register_types.assert_called_with({'typ': 'def'})
ros1_to_cdr.assert_has_calls([call(b'\x42', 'typ'), call(b'\x43', 'typ')])
writer.return_value.__enter__.return_value.add_connection.side_effect = [
wconnections[0],
wconnections[1],
]
ros1_to_cdr.side_effect = KeyError('exc')
with pytest.raises(ConverterError, match='Converting rosbag: '):
with pytest.raises(ConverterError, match='Converting rosbag: .*exc'):
convert(Path('foo.bag'), None)
writer.side_effect = WriterError('exc')
with pytest.raises(ConverterError, match='Writing destination bag: '):
with pytest.raises(ConverterError, match='Writing destination bag: exc'):
convert(Path('foo.bag'), None)
reader.side_effect = ReaderError('exc')
with pytest.raises(ConverterError, match='Reading source bag: '):
with pytest.raises(ConverterError, match='Reading source bag: exc'):
convert(Path('foo.bag'), None)
def test_convert_2to1(tmp_path: Path) -> None:
"""Test conversion from rosbag2 to rosbag1."""
(tmp_path / 'subdir').mkdir()
(tmp_path / 'foo.bag').write_text('')
with pytest.raises(ConverterError, match='exists already'):
convert(Path('subdir'), tmp_path / 'foo.bag')
with patch('rosbags.convert.converter.Reader2') as reader, \
patch('rosbags.convert.converter.Writer1') as writer, \
patch('rosbags.convert.converter.cdr_to_ros1') as cdr_to_ros1:
connections = [
Mock(topic='/topic', msgtype='std_msgs/msg/Bool', offered_qos_profiles=''),
Mock(topic='/topic', msgtype='std_msgs/msg/Bool', offered_qos_profiles=LATCH),
]
wconnections = [
Mock(topic='/topic', msgtype='typ'),
Mock(topic='/topic', msgtype='typ'),
]
reader.return_value.__enter__.return_value.connections = {
1: connections[0],
2: connections[1],
}
reader.return_value.__enter__.return_value.messages.return_value = [
(connections[0], 42, b'\x42'),
(connections[1], 43, b'\x43'),
]
writer.return_value.__enter__.return_value.add_connection.side_effect = [
wconnections[0],
wconnections[1],
]
cdr_to_ros1.return_value = b'666'
convert(Path('foo'), None)
reader.assert_called_with(Path('foo'))
reader.return_value.__enter__.return_value.messages.assert_called_with()
writer.assert_called_with(Path('foo.bag'))
writer.return_value.__enter__.return_value.add_connection.assert_has_calls(
[
call(
'/topic',
'std_msgs/msg/Bool',
'bool data\n',
'8b94c1b53db61fb6aed406028ad6332a',
None,
0,
),
call(
'/topic',
'std_msgs/msg/Bool',
'bool data\n',
'8b94c1b53db61fb6aed406028ad6332a',
None,
1,
),
],
)
writer.return_value.__enter__.return_value.write.assert_has_calls(
[call(wconnections[0], 42, b'666'),
call(wconnections[1], 43, b'666')],
)
cdr_to_ros1.assert_has_calls(
[
call(b'\x42', 'std_msgs/msg/Bool'),
call(b'\x43', 'std_msgs/msg/Bool'),
],
)
writer.return_value.__enter__.return_value.add_connection.side_effect = [
wconnections[0],
wconnections[1],
]
cdr_to_ros1.side_effect = KeyError('exc')
with pytest.raises(ConverterError, match='Converting rosbag: .*exc'):
convert(Path('foo'), None)
writer.side_effect = WriterError('exc')
with pytest.raises(ConverterError, match='Writing destination bag: exc'):
convert(Path('foo'), None)
reader.side_effect = ReaderError('exc')
with pytest.raises(ConverterError, match='Reading source bag: exc'):
convert(Path('foo'), None)