Skip to content

Commit ef72cbd

Browse files
committed
Please linters + improve test setup and teardown
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
1 parent 9f357e8 commit ef72cbd

File tree

2 files changed

+34
-43
lines changed

2 files changed

+34
-43
lines changed

rclpy/rclpy/qos_overriding_options.py

Lines changed: 12 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,8 @@
2626
from rclpy.node import Node
2727
from rclpy.parameter import Parameter
2828
from rclpy.publisher import Publisher
29-
from rclpy.qos import QoSProfile
3029
from rclpy.qos import QoSPolicyKind
30+
from rclpy.qos import QoSProfile
3131
from rclpy.subscription import Subscription
3232

3333

@@ -36,29 +36,27 @@ class InvalidQosOverridesError(Exception):
3636

3737

3838
class QoSOverridingOptions:
39-
"""
40-
Options to customize qos parameter overrides.
41-
"""
39+
"""Options to customize qos parameter overrides."""
4240

4341
def __init__(
4442
self,
4543
*,
4644
policy_kinds: Iterable[QoSPolicyKind],
4745
callback: Optional[Callable[[QoSProfile], bool]] = None,
48-
id: Optional[Text] = None
46+
entity_id: Optional[Text] = None
4947
):
5048
"""
5149
Construct a QoSOverridingOptions object.
5250
5351
:param policy_kinds: Qos kinds that will have a declared parameter.
5452
:param callback: Callback that will be used to validate the qos profile
5553
after the paramter overrides get applied.
56-
:param id: Optional identifier, to disambiguate in the case that different qos
54+
:param entity_id: Optional identifier, to disambiguate in the case that different qos
5755
policies for the same topic are desired.
5856
"""
5957
self._policy_kinds = policy_kinds
6058
self._callback = callback
61-
self._id = id
59+
self._entity_id = entity_id
6260

6361
@property
6462
def policy_kinds(self) -> Iterable[QoSPolicyKind]:
@@ -71,20 +69,20 @@ def callback(self) -> Optional[Callable[[QoSProfile], bool]]:
7169
return self._callback
7270

7371
@property
74-
def id(self) -> Optional[Text]:
72+
def entity_id(self) -> Optional[Text]:
7573
"""Get the optional entity id."""
76-
return self._id
74+
return self._entity_id
7775

7876
@classmethod
7977
def with_default_policies(
8078
cls, *,
8179
callback: Optional[Callable[[QoSProfile], bool]] = None,
82-
id: Optional[Text] = None
80+
entity_id: Optional[Text] = None
8381
) -> 'QoSOverridingOptions':
8482
return cls(
8583
policy_kinds=(QoSPolicyKind.HISTORY, QoSPolicyKind.DEPTH, QoSPolicyKind.RELIABILITY),
8684
callback=callback,
87-
id=id,
85+
entity_id=entity_id,
8886
)
8987

9088

@@ -95,8 +93,7 @@ def _declare_qos_parameteres(
9593
qos: QoSProfile,
9694
options: QoSOverridingOptions) -> QoSProfile:
9795
"""
98-
Internal.
99-
Declares qos parameters for a Publisher or a Subscription.
96+
Internal, declare qos parameters for a Publisher or a Subscription.
10097
10198
:param entity_type: Either `rclpy.node.Publisher` or `rclpy.node.Subscription`.
10299
:param node: Node used to declare the parameters.
@@ -108,9 +105,9 @@ def _declare_qos_parameteres(
108105
if not issubclass(entity_type, (Publisher, Subscription)):
109106
raise TypeError("Argument `entity_type` should be a subclass of Publisher or Subscription")
110107
entity_type_str = 'publisher' if issubclass(entity_type, Publisher) else Subscription
111-
id_suffix = '' if options.id is None else f'_{options.id}'
108+
id_suffix = '' if options.entity_id is None else f'_{options.entity_id}'
112109
name = f'qos_overrides.{topic_name}.{entity_type_str}{id_suffix}.' '{}'
113-
description = '{}' f' for {entity_type_str} `{topic_name}` with id `{id}`'
110+
description = '{}' f' for {entity_type_str} `{topic_name}` with id `{options.entity_id}`'
114111
allowed_policies = _get_allowed_policies(entity_type)
115112
for policy in options.policy_kinds:
116113
if policy not in allowed_policies:
@@ -153,12 +150,6 @@ def _get_qos_policy_parameter(qos: QoSProfile, policy: QoSPolicyKind) -> Paramet
153150

154151

155152
def _override_qos_policy_with_param(qos: QoSProfile, policy: QoSPolicyKind, param: Parameter):
156-
# policy_enum_map = {
157-
# QoSPolicyKind.LIVELINESS: rclpy.qos.LivelinessPolicy,
158-
# QoSPolicyKind.RELIABILITY: rclpy.qos.LivelinessPolicy,
159-
# QoSPolicyKind.LIVELINESS: rclpy.qos.LivelinessPolicy,
160-
# QoSPolicyKind.LIVELINESS: rclpy.qos.LivelinessPolicy,
161-
# }
162153
value = param.value
163154
policy_name = policy.name.lower()
164155
if policy in (

rclpy/test/test_qos_overriding_options.py

Lines changed: 22 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -18,15 +18,22 @@
1818
from rclpy.node import Node
1919
from rclpy.parameter import Parameter
2020
from rclpy.publisher import Publisher
21-
from rclpy.qos import QoSPolicyKind, QoSProfile
21+
from rclpy.qos import QoSPolicyKind
22+
from rclpy.qos import QoSProfile
2223
from rclpy.qos_overriding_options import _declare_qos_parameteres
2324
from rclpy.qos_overriding_options import InvalidQosOverridesError
2425
from rclpy.qos_overriding_options import QoSOverridingOptions
2526

2627

27-
def test_declare_qos_parameters():
28+
@pytest.fixture(autouse=True)
29+
def init_shutdown():
2830
rclpy.init()
29-
node = Node("my_node")
31+
yield
32+
rclpy.shutdown()
33+
34+
35+
def test_declare_qos_parameters():
36+
node = Node('my_node')
3037
_declare_qos_parameteres(
3138
Publisher, node, '/my_topic', QoSProfile(depth=10),
3239
QoSOverridingOptions.with_default_policies()
@@ -38,18 +45,15 @@ def test_declare_qos_parameters():
3845
('/my_topic.publisher.history', 'keep_last'),
3946
('/my_topic.publisher.reliability', 'reliable'),
4047
)
41-
for actual, expected in zip (
48+
for actual, expected in zip(
4249
sorted(qos_overrides.items(), key=lambda x: x[0]), expected_params
4350
):
4451
assert actual[0] == expected[0] # same param name
4552
assert actual[1].value == expected[1] # same param value
4653

47-
rclpy.shutdown()
48-
4954

5055
def test_declare_qos_parameters_with_overrides():
51-
rclpy.init()
52-
node = Node("my_node", parameter_overrides=[
56+
node = Node('my_node', parameter_overrides=[
5357
Parameter('qos_overrides./my_topic.publisher.depth', value=100),
5458
Parameter('qos_overrides./my_topic.publisher.reliability', value='best_effort'),
5559
])
@@ -64,17 +68,14 @@ def test_declare_qos_parameters_with_overrides():
6468
('/my_topic.publisher.history', 'keep_last'),
6569
('/my_topic.publisher.reliability', 'best_effort'),
6670
)
67-
for actual, expected in zip (
71+
for actual, expected in zip(
6872
sorted(qos_overrides.items(), key=lambda x: x[0]), expected_params
6973
):
7074
assert actual[0] == expected[0] # same param name
7175
assert actual[1].value == expected[1] # same param value
7276

73-
rclpy.shutdown()
74-
7577

7678
def test_declare_qos_parameters_with_happy_callback():
77-
rclpy.init()
7879
node = Node("my_node")
7980
_declare_qos_parameteres(
8081
Publisher, node, '/my_topic', QoSProfile(depth=10),
@@ -87,27 +88,28 @@ def test_declare_qos_parameters_with_happy_callback():
8788
('/my_topic.publisher.history', 'keep_last'),
8889
('/my_topic.publisher.reliability', 'reliable'),
8990
)
90-
rclpy.shutdown()
91+
for actual, expected in zip(
92+
sorted(qos_overrides.items(), key=lambda x: x[0]), expected_params
93+
):
94+
assert actual[0] == expected[0] # same param name
95+
assert actual[1].value == expected[1] # same param value
9196

9297

9398
def test_declare_qos_parameters_with_unhappy_callback():
94-
rclpy.init()
95-
node = Node("my_node")
99+
node = Node('my_node')
96100

97101
with pytest.raises(InvalidQosOverridesError):
98102
_declare_qos_parameteres(
99103
Publisher, node, '/my_topic', QoSProfile(depth=10),
100104
QoSOverridingOptions.with_default_policies(callback=lambda x: False)
101105
)
102-
rclpy.shutdown()
103106

104107

105108
def test_declare_qos_parameters_with_id():
106-
rclpy.init()
107-
node = Node("my_node")
109+
node = Node('my_node')
108110
_declare_qos_parameteres(
109111
Publisher, node, '/my_topic', QoSProfile(depth=10),
110-
QoSOverridingOptions.with_default_policies(id='i_have_an_id')
112+
QoSOverridingOptions.with_default_policies(entity_id='i_have_an_id')
111113
)
112114
qos_overrides = node.get_parameters_by_prefix('qos_overrides')
113115
assert len(qos_overrides) == 3
@@ -116,10 +118,8 @@ def test_declare_qos_parameters_with_id():
116118
('/my_topic.publisher_i_have_an_id.history', 'keep_last'),
117119
('/my_topic.publisher_i_have_an_id.reliability', 'reliable'),
118120
)
119-
for actual, expected in zip (
121+
for actual, expected in zip(
120122
sorted(qos_overrides.items(), key=lambda x: x[0]), expected_params
121123
):
122124
assert actual[0] == expected[0] # same param name
123125
assert actual[1].value == expected[1] # same param value
124-
125-
rclpy.shutdown()

0 commit comments

Comments
 (0)