1818from rclpy .node import Node
1919from rclpy .parameter import Parameter
2020from rclpy .publisher import Publisher
21- from rclpy .qos import QoSPolicyKind , QoSProfile
21+ from rclpy .qos import QoSPolicyKind
22+ from rclpy .qos import QoSProfile
2223from rclpy .qos_overriding_options import _declare_qos_parameteres
2324from rclpy .qos_overriding_options import InvalidQosOverridesError
2425from 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
5055def 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
7678def 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
9398def 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
105108def 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