Skip to content

Commit b84db65

Browse files
authored
added type hinting to launch_testing_ros/test/examples (#386)
Signed-off-by: yaswanth <[email protected]>
1 parent bc60978 commit b84db65

File tree

6 files changed

+33
-17
lines changed

6 files changed

+33
-17
lines changed

launch_testing_ros/test/examples/check_msgs_launch_test.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
import launch.actions
2424
import launch_ros.actions
2525
import launch_testing.actions
26+
from launch_testing.io_handler import ActiveIoHandler
2627
import launch_testing.markers
2728
import pytest
2829
import rclpy
@@ -49,7 +50,7 @@ def generate_test_description():
4950

5051
class TestFixture(unittest.TestCase):
5152

52-
def test_check_if_msgs_published(self, proc_output):
53+
def test_check_if_msgs_published(self, proc_output: ActiveIoHandler):
5354
rclpy.init()
5455
try:
5556
node = MakeTestNode('test_node')
@@ -62,7 +63,7 @@ def test_check_if_msgs_published(self, proc_output):
6263

6364
class MakeTestNode(Node):
6465

65-
def __init__(self, name='test_node'):
66+
def __init__(self, name: str = 'test_node'):
6667
super().__init__(name)
6768
self.msg_event_object = Event()
6869

@@ -79,5 +80,5 @@ def start_subscriber(self):
7980
self.ros_spin_thread = Thread(target=lambda node: rclpy.spin(node), args=(self,))
8081
self.ros_spin_thread.start()
8182

82-
def subscriber_callback(self, data):
83+
def subscriber_callback(self, data: String):
8384
self.msg_event_object.set()

launch_testing_ros/test/examples/check_node_launch_test.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
import launch.actions
2222
import launch_ros.actions
2323
import launch_testing.actions
24+
from launch_testing.io_handler import ActiveIoHandler
2425
import launch_testing.markers
2526
import pytest
2627
import rclpy
@@ -49,7 +50,7 @@ def generate_test_description():
4950

5051
class TestFixture(unittest.TestCase):
5152

52-
def test_node_start(self, proc_output):
53+
def test_node_start(self, proc_output: ActiveIoHandler):
5354
rclpy.init()
5455
try:
5556
node = MakeTestNode('test_node')
@@ -60,10 +61,10 @@ def test_node_start(self, proc_output):
6061

6162
class MakeTestNode(Node):
6263

63-
def __init__(self, name='test_node'):
64+
def __init__(self, name: str = 'test_node'):
6465
super().__init__(name)
6566

66-
def wait_for_node(self, node_name, timeout=8.0):
67+
def wait_for_node(self, node_name: str, timeout: float = 8.0):
6768
start = time.time()
6869
flag = False
6970
print('Waiting for node...')

launch_testing_ros/test/examples/listener.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ def __init__(self):
2626
String, 'chatter', self.callback, 10
2727
)
2828

29-
def callback(self, msg):
29+
def callback(self, msg: String):
3030
self.get_logger().info('I heard: [%s]' % msg.data)
3131

3232

launch_testing_ros/test/examples/set_param_launch_test.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
import launch.actions
2121
import launch_ros.actions
2222
import launch_testing.actions
23+
from launch_testing.io_handler import ActiveIoHandler
2324
import launch_testing.markers
2425
import pytest
2526
from rcl_interfaces.srv import SetParameters
@@ -45,7 +46,7 @@ def generate_test_description():
4546

4647
class TestFixture(unittest.TestCase):
4748

48-
def test_set_parameter(self, proc_output):
49+
def test_set_parameter(self, proc_output: ActiveIoHandler):
4950
rclpy.init()
5051
try:
5152
node = MakeTestNode('test_node')
@@ -57,10 +58,10 @@ def test_set_parameter(self, proc_output):
5758

5859
class MakeTestNode(Node):
5960

60-
def __init__(self, name='test_node'):
61+
def __init__(self, name: str = 'test_node'):
6162
super().__init__(name)
6263

63-
def set_parameter(self, state=True, timeout=5.0):
64+
def set_parameter(self, state: bool = True, timeout: float = 5.0):
6465
parameters = [rclpy.Parameter('demo_parameter_1', value=state).to_parameter_msg()]
6566

6667
client = self.create_client(SetParameters, 'demo_node_1/set_parameters')

launch_testing_ros/test/examples/talker_listener_launch_test.py

Lines changed: 17 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -19,16 +19,20 @@
1919
import uuid
2020

2121
import launch
22+
from launch.launch_service import LaunchService
2223
import launch_ros
2324
import launch_ros.actions
2425
import launch_testing.actions
26+
from launch_testing.io_handler import ActiveIoHandler
2527
import launch_testing_ros
2628

2729
import pytest
2830

2931
import rclpy
32+
from rclpy.node import Node
3033

3134
import std_msgs.msg
35+
from std_msgs.msg import String
3236

3337

3438
@pytest.mark.rostest
@@ -86,7 +90,10 @@ def setUp(self):
8690
def tearDown(self):
8791
self.node.destroy_node()
8892

89-
def test_talker_transmits(self, launch_service, talker, proc_output):
93+
def test_talker_transmits(self,
94+
launch_service: LaunchService,
95+
talker: Node,
96+
proc_output: ActiveIoHandler):
9097
# Expect the talker to publish strings on '/talker_chatter' and also write to stdout
9198
msgs_rx = []
9299

@@ -114,7 +121,10 @@ def test_talker_transmits(self, launch_service, talker, proc_output):
114121
finally:
115122
self.node.destroy_subscription(sub)
116123

117-
def test_listener_receives(self, launch_service, listener, proc_output):
124+
def test_listener_receives(self,
125+
launch_service: LaunchService,
126+
listener: Node,
127+
proc_output: ActiveIoHandler):
118128
pub = self.node.create_publisher(
119129
std_msgs.msg.String,
120130
'listener_chatter',
@@ -138,10 +148,13 @@ def test_listener_receives(self, launch_service, listener, proc_output):
138148
finally:
139149
self.node.destroy_publisher(pub)
140150

141-
def test_fuzzy_data(self, launch_service, listener, proc_output):
151+
def test_fuzzy_data(self,
152+
launch_service: LaunchService,
153+
listener: Node,
154+
proc_output: ActiveIoHandler):
142155
# This test shows how to insert a node in between the talker and the listener to
143156
# change the data. Here we're going to change 'Hello World' to 'Aloha World'
144-
def data_mangler(msg):
157+
def data_mangler(msg: String):
145158
msg.data = msg.data.replace('Hello', 'Aloha')
146159
return msg
147160

launch_testing_ros/test/examples/wait_for_topic_launch_test.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929
from std_msgs.msg import String
3030

3131

32-
def generate_node(i):
32+
def generate_node(i: int):
3333
"""Return node and remap the topic based on the index provided."""
3434
path_to_test = os.path.dirname(__file__)
3535
return launch_ros.actions.Node(
@@ -56,7 +56,7 @@ def generate_test_description():
5656
if os.name != 'nt':
5757
class TestFixture(unittest.TestCase):
5858

59-
def test_topics_successful(self, count):
59+
def test_topics_successful(self, count: int):
6060
"""All the supplied topics should be read successfully."""
6161
topic_list = [('chatter_' + str(i), String) for i in range(count)]
6262
expected_topics = {'chatter_' + str(i) for i in range(count)}
@@ -86,7 +86,7 @@ def test_topics_successful(self, count):
8686
assert message_pattern.match(message)
8787
wait_for_node_object_2.shutdown()
8888

89-
def test_topics_unsuccessful(self, count):
89+
def test_topics_unsuccessful(self, count: int):
9090
"""All topics should be read except for the 'invalid_topic'."""
9191
topic_list = [('chatter_' + str(i), String) for i in range(count)]
9292
# Add a topic that will never have anything published on it

0 commit comments

Comments
 (0)