@@ -256,15 +256,45 @@ def test_list_count(self):
256256 assert int (output_lines [0 ]) == 9
257257
258258 @launch_testing .markers .retry_on_failure (times = 5 )
259- def test_topic_info (self ):
259+ def test_topic_endpoint_info (self ):
260260 with self .launch_topic_command (arguments = ['info' , '/chatter' ]) as topic_command :
261261 assert topic_command .wait_for_shutdown (timeout = 10 )
262262 assert topic_command .exit_code == launch_testing .asserts .EXIT_OK
263263 assert launch_testing .tools .expect_output (
264264 expected_lines = [
265265 'Type: std_msgs/msg/String' ,
266266 'Publisher count: 1' ,
267- 'Subscriber count: 0'
267+ 'Subscription count: 0'
268+ ],
269+ text = topic_command .output ,
270+ strict = True
271+ )
272+
273+ @launch_testing .markers .retry_on_failure (times = 5 )
274+ def test_topic_endpoint_info_verbose (self ):
275+ with self .launch_topic_command (arguments = ['info' , '-v' , '/chatter' ]) as topic_command :
276+ assert topic_command .wait_for_shutdown (timeout = 10 )
277+ assert topic_command .exit_code == launch_testing .asserts .EXIT_OK
278+ assert launch_testing .tools .expect_output (
279+ expected_lines = [
280+ 'Type: std_msgs/msg/String' ,
281+ '' ,
282+ 'Publisher count: 1' ,
283+ '' ,
284+ re .compile (r'Node name: \w+' ),
285+ 'Node namespace: /' ,
286+ 'Topic type: std_msgs/msg/String' ,
287+ re .compile (r'Endpoint type: (INVALID|PUBLISHER|SUBSCRIPTION)' ),
288+ re .compile (r'GID: [\w\.]+' ),
289+ 'QoS profile:' ,
290+ re .compile (r' Reliability: RMW_QOS_POLICY_RELIABILITY_\w+' ),
291+ re .compile (r' Durability: RMW_QOS_POLICY_DURABILITY_\w+' ),
292+ re .compile (r' Lifespan: \d+ nanoseconds' ),
293+ re .compile (r' Deadline: \d+ nanoseconds' ),
294+ re .compile (r' Liveliness: RMW_QOS_POLICY_LIVELINESS_\w+' ),
295+ re .compile (r' Liveliness lease duration: \d+ nanoseconds' ),
296+ '' ,
297+ 'Subscription count: 0'
268298 ],
269299 text = topic_command .output ,
270300 strict = True
@@ -517,7 +547,7 @@ def test_topic_pub(self):
517547 ), timeout = 10 )
518548 assert self .listener_node .wait_for_output (functools .partial (
519549 launch_testing .tools .expect_output , expected_lines = [
520- re .compile (r'\[INFO\] \[\d+.\d*\] \[listener\]: I heard: \[foo\]' )
550+ re .compile (r'\[INFO\] \[\d+\ .\d*\] \[listener\]: I heard: \[foo\]' )
521551 ] * 3 , strict = False
522552 ), timeout = 10 )
523553 assert topic_command .wait_for_shutdown (timeout = 10 )
@@ -541,7 +571,7 @@ def test_topic_pub_once(self):
541571 assert topic_command .wait_for_shutdown (timeout = 10 )
542572 assert self .listener_node .wait_for_output (functools .partial (
543573 launch_testing .tools .expect_output , expected_lines = [
544- re .compile (r'\[INFO\] \[\d+.\d*\] \[listener\]: I heard: \[bar\]' )
574+ re .compile (r'\[INFO\] \[\d+\ .\d*\] \[listener\]: I heard: \[bar\]' )
545575 ], strict = False
546576 ), timeout = 10 )
547577 assert topic_command .exit_code == launch_testing .asserts .EXIT_OK
@@ -567,7 +597,7 @@ def test_topic_pub_print_every_two(self):
567597 ), timeout = 10 ), 'Output does not match: ' + topic_command .output
568598 assert self .listener_node .wait_for_output (functools .partial (
569599 launch_testing .tools .expect_output , expected_lines = [
570- re .compile (r'\[INFO\] \[\d+.\d*\] \[listener\]: I heard: \[fizz\]' )
600+ re .compile (r'\[INFO\] \[\d+\ .\d*\] \[listener\]: I heard: \[fizz\]' )
571601 ], strict = False
572602 ), timeout = 10 )
573603 assert topic_command .wait_for_shutdown (timeout = 10 )
0 commit comments