Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix launch_testing_ros example #121

Merged
merged 1 commit into from
Jan 31, 2020
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 26 additions & 19 deletions launch_testing_ros/test/examples/talker_listener_launch_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@

import pytest

import rclpy

import std_msgs.msg


Expand Down Expand Up @@ -67,15 +69,28 @@ def generate_test_description():

class TestTalkerListenerLink(unittest.TestCase):

def test_talker_transmits(self, launch_service, talker, proc_output):
# Get launch context ROS node
launch_context = launch_service.context
node = launch_context.locals.launch_ros_node
@classmethod
def setUpClass(cls):
# Initialize the ROS context for the test node
rclpy.init()

@classmethod
def tearDownClass(cls):
# Shutdown the ROS context
rclpy.shutdown()

def setUp(self):
# Create a ROS node for tests
self.node = rclpy.create_node('test_talker_listener_link')

def tearDown(self):
self.node.destroy_node()

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

sub = node.create_subscription(
sub = self.node.create_subscription(
std_msgs.msg.String,
'talker_chatter',
lambda msg: msgs_rx.append(msg),
Expand All @@ -85,7 +100,7 @@ def test_talker_transmits(self, launch_service, talker, proc_output):
# Wait until the talker transmits two messages over the ROS topic
end_time = time.time() + 10
while time.time() < end_time:
time.sleep(1.0)
rclpy.spin_once(self.node, timeout_sec=0.1)
if len(msgs_rx) > 2:
break

Expand All @@ -97,14 +112,10 @@ def test_talker_transmits(self, launch_service, talker, proc_output):
expected_output=msg.data, process=talker
)
finally:
node.destroy_subscription(sub)
self.node.destroy_subscription(sub)

def test_listener_receives(self, launch_service, listener, proc_output):
# Get launch context ROS node
launch_context = launch_service.context
node = launch_context.locals.launch_ros_node

pub = node.create_publisher(
pub = self.node.create_publisher(
std_msgs.msg.String,
'listener_chatter',
10
Expand All @@ -125,21 +136,17 @@ def test_listener_receives(self, launch_service, listener, proc_output):
break
assert success, 'Waiting for output timed out'
finally:
node.destroy_publisher(pub)
self.node.destroy_publisher(pub)

def test_fuzzy_data(self, launch_service, listener, proc_output):
# Get launch context ROS node
launch_context = launch_service.context
node = launch_context.locals.launch_ros_node

# 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):
msg.data = msg.data.replace('Hello', 'Aloha')
return msg

republisher = launch_testing_ros.DataRepublisher(
node,
self.node,
'talker_chatter',
'listener_chatter',
std_msgs.msg.String,
Expand All @@ -149,7 +156,7 @@ def data_mangler(msg):
# Spin for a few seconds until we've republished some mangled messages
end_time = time.time() + 10
while time.time() < end_time:
time.sleep(1.0)
rclpy.spin_once(self.node, timeout_sec=0.1)
if republisher.get_num_republished() > 2:
break

Expand Down