Translate latching info to equivalent QoS settings

This commit is contained in:
Marko Durkovic 2021-07-03 17:26:49 +02:00
parent c2bbeec7aa
commit 5175c349aa
2 changed files with 44 additions and 5 deletions

View File

@ -15,6 +15,24 @@ if TYPE_CHECKING:
from pathlib import Path from pathlib import Path
from typing import Any, Dict, Optional from typing import Any, Dict, Optional
LATCH = """
- history: 3
depth: 0
reliability: 1
durability: 1
deadline:
sec: 2147483647
nsec: 4294967295
lifespan:
sec: 2147483647
nsec: 4294967295
liveliness: 1
liveliness_lease_duration:
sec: 2147483647
nsec: 4294967295
avoid_ros_namespace_conventions: false
""".strip()
class ConverterError(Exception): class ConverterError(Exception):
"""Converter Error.""" """Converter Error."""
@ -40,7 +58,14 @@ def convert(src: Path, dst: Optional[Path]) -> None:
with Reader(src) as reader, Writer(dst) as writer: with Reader(src) as reader, Writer(dst) as writer:
typs: Dict[str, Any] = {} typs: Dict[str, Any] = {}
for name, topic in reader.topics.items(): for name, topic in reader.topics.items():
writer.add_topic(name, topic.msgtype) connection = next( # pragma: no branch
x for x in reader.connections.values() if x.topic == name
)
writer.add_topic(
name,
topic.msgtype,
offered_qos_profiles=LATCH if connection.latching else '',
)
typs.update(get_types_from_msg(topic.msgdef, topic.msgtype)) typs.update(get_types_from_msg(topic.msgdef, topic.msgtype))
register_types(typs) register_types(typs)

View File

@ -4,12 +4,13 @@
import sys import sys
from pathlib import Path from pathlib import Path
from unittest.mock import Mock, patch from unittest.mock import Mock, call, patch
import pytest import pytest
from rosbags.convert import ConverterError, convert from rosbags.convert import ConverterError, convert
from rosbags.convert.__main__ import main from rosbags.convert.__main__ import main
from rosbags.convert.converter import LATCH
from rosbags.rosbag1 import ReaderError from rosbags.rosbag1 import ReaderError
from rosbags.rosbag2 import WriterError from rosbags.rosbag2 import WriterError
@ -75,11 +76,17 @@ def test_convert(tmp_path: Path):
patch('rosbags.convert.converter.register_types') as register_types, \ patch('rosbags.convert.converter.register_types') as register_types, \
patch('rosbags.convert.converter.ros1_to_cdr') as ros1_to_cdr: patch('rosbags.convert.converter.ros1_to_cdr') as ros1_to_cdr:
reader.return_value.__enter__.return_value.connections = {
0: Mock(topic='/topic', latching=False),
1: Mock(topic='/latched', latching=True),
}
reader.return_value.__enter__.return_value.topics = { reader.return_value.__enter__.return_value.topics = {
'/topic': Mock(msgtype='typ', msgdef='def'), '/topic': Mock(msgtype='typ', msgdef='def'),
'/latched': Mock(msgtype='typ', msgdef='def'),
} }
reader.return_value.__enter__.return_value.messages.return_value = [ reader.return_value.__enter__.return_value.messages.return_value = [
('/topic', 'typ', 42, b'\x42'), ('/topic', 'typ', 42, b'\x42'),
('/latched', 'typ', 43, b'\x43'),
] ]
ros1_to_cdr.return_value = b'666' ros1_to_cdr.return_value = b'666'
@ -90,11 +97,18 @@ def test_convert(tmp_path: Path):
reader.return_value.__enter__.return_value.messages.assert_called_with() reader.return_value.__enter__.return_value.messages.assert_called_with()
writer.assert_called_with(Path('foo')) writer.assert_called_with(Path('foo'))
writer.return_value.__enter__.return_value.add_topic.assert_called_with('/topic', 'typ') writer.return_value.__enter__.return_value.add_topic.assert_has_calls(
writer.return_value.__enter__.return_value.write.assert_called_with('/topic', 42, b'666') [
call('/topic', 'typ', offered_qos_profiles=''),
call('/latched', 'typ', offered_qos_profiles=LATCH),
],
)
writer.return_value.__enter__.return_value.write.assert_has_calls(
[call('/topic', 42, b'666'), call('/latched', 43, b'666')],
)
register_types.assert_called_with({'typ': 'def'}) register_types.assert_called_with({'typ': 'def'})
ros1_to_cdr.assert_called_with(b'\x42', 'typ') ros1_to_cdr.assert_has_calls([call(b'\x42', 'typ'), call(b'\x43', 'typ')])
ros1_to_cdr.side_effect = KeyError('exc') ros1_to_cdr.side_effect = KeyError('exc')
with pytest.raises(ConverterError, match='Converting rosbag: '): with pytest.raises(ConverterError, match='Converting rosbag: '):