Skip to content

Commit

Permalink
added type hinting to launch_testing_ros/test/examples (#386)
Browse files Browse the repository at this point in the history
Signed-off-by: yaswanth <gonnayaswanth17@gmail.com>
  • Loading branch information
yaswanth1701 authored Nov 21, 2023
1 parent bc60978 commit b84db65
Show file tree
Hide file tree
Showing 6 changed files with 33 additions and 17 deletions.
7 changes: 4 additions & 3 deletions launch_testing_ros/test/examples/check_msgs_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
import launch.actions
import launch_ros.actions
import launch_testing.actions
from launch_testing.io_handler import ActiveIoHandler
import launch_testing.markers
import pytest
import rclpy
Expand All @@ -49,7 +50,7 @@ def generate_test_description():

class TestFixture(unittest.TestCase):

def test_check_if_msgs_published(self, proc_output):
def test_check_if_msgs_published(self, proc_output: ActiveIoHandler):
rclpy.init()
try:
node = MakeTestNode('test_node')
Expand All @@ -62,7 +63,7 @@ def test_check_if_msgs_published(self, proc_output):

class MakeTestNode(Node):

def __init__(self, name='test_node'):
def __init__(self, name: str = 'test_node'):
super().__init__(name)
self.msg_event_object = Event()

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

def subscriber_callback(self, data):
def subscriber_callback(self, data: String):
self.msg_event_object.set()
7 changes: 4 additions & 3 deletions launch_testing_ros/test/examples/check_node_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
import launch.actions
import launch_ros.actions
import launch_testing.actions
from launch_testing.io_handler import ActiveIoHandler
import launch_testing.markers
import pytest
import rclpy
Expand Down Expand Up @@ -49,7 +50,7 @@ def generate_test_description():

class TestFixture(unittest.TestCase):

def test_node_start(self, proc_output):
def test_node_start(self, proc_output: ActiveIoHandler):
rclpy.init()
try:
node = MakeTestNode('test_node')
Expand All @@ -60,10 +61,10 @@ def test_node_start(self, proc_output):

class MakeTestNode(Node):

def __init__(self, name='test_node'):
def __init__(self, name: str = 'test_node'):
super().__init__(name)

def wait_for_node(self, node_name, timeout=8.0):
def wait_for_node(self, node_name: str, timeout: float = 8.0):
start = time.time()
flag = False
print('Waiting for node...')
Expand Down
2 changes: 1 addition & 1 deletion launch_testing_ros/test/examples/listener.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ def __init__(self):
String, 'chatter', self.callback, 10
)

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


Expand Down
7 changes: 4 additions & 3 deletions launch_testing_ros/test/examples/set_param_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
import launch.actions
import launch_ros.actions
import launch_testing.actions
from launch_testing.io_handler import ActiveIoHandler
import launch_testing.markers
import pytest
from rcl_interfaces.srv import SetParameters
Expand All @@ -45,7 +46,7 @@ def generate_test_description():

class TestFixture(unittest.TestCase):

def test_set_parameter(self, proc_output):
def test_set_parameter(self, proc_output: ActiveIoHandler):
rclpy.init()
try:
node = MakeTestNode('test_node')
Expand All @@ -57,10 +58,10 @@ def test_set_parameter(self, proc_output):

class MakeTestNode(Node):

def __init__(self, name='test_node'):
def __init__(self, name: str = 'test_node'):
super().__init__(name)

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

client = self.create_client(SetParameters, 'demo_node_1/set_parameters')
Expand Down
21 changes: 17 additions & 4 deletions launch_testing_ros/test/examples/talker_listener_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,16 +19,20 @@
import uuid

import launch
from launch.launch_service import LaunchService
import launch_ros
import launch_ros.actions
import launch_testing.actions
from launch_testing.io_handler import ActiveIoHandler
import launch_testing_ros

import pytest

import rclpy
from rclpy.node import Node

import std_msgs.msg
from std_msgs.msg import String


@pytest.mark.rostest
Expand Down Expand Up @@ -86,7 +90,10 @@ def setUp(self):
def tearDown(self):
self.node.destroy_node()

def test_talker_transmits(self, launch_service, talker, proc_output):
def test_talker_transmits(self,
launch_service: LaunchService,
talker: Node,
proc_output: ActiveIoHandler):
# Expect the talker to publish strings on '/talker_chatter' and also write to stdout
msgs_rx = []

Expand Down Expand Up @@ -114,7 +121,10 @@ def test_talker_transmits(self, launch_service, talker, proc_output):
finally:
self.node.destroy_subscription(sub)

def test_listener_receives(self, launch_service, listener, proc_output):
def test_listener_receives(self,
launch_service: LaunchService,
listener: Node,
proc_output: ActiveIoHandler):
pub = self.node.create_publisher(
std_msgs.msg.String,
'listener_chatter',
Expand All @@ -138,10 +148,13 @@ def test_listener_receives(self, launch_service, listener, proc_output):
finally:
self.node.destroy_publisher(pub)

def test_fuzzy_data(self, launch_service, listener, proc_output):
def test_fuzzy_data(self,
launch_service: LaunchService,
listener: Node,
proc_output: ActiveIoHandler):
# This test shows how to insert a node in between the talker and the listener to
# change the data. Here we're going to change 'Hello World' to 'Aloha World'
def data_mangler(msg):
def data_mangler(msg: String):
msg.data = msg.data.replace('Hello', 'Aloha')
return msg

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
from std_msgs.msg import String


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

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

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

0 comments on commit b84db65

Please sign in to comment.