|
| 1 | +# Copyright 2019 Apex.AI, Inc. |
| 2 | +# |
| 3 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +# you may not use this file except in compliance with the License. |
| 5 | +# You may obtain a copy of the License at |
| 6 | +# |
| 7 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +# |
| 9 | +# Unless required by applicable law or agreed to in writing, software |
| 10 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +# See the License for the specific language governing permissions and |
| 13 | +# limitations under the License. |
| 14 | + |
| 15 | +import os |
| 16 | +import time |
| 17 | +import unittest |
| 18 | +import uuid |
| 19 | + |
| 20 | +from apex_launchtest.util import NoMatchingProcessException |
| 21 | +import apex_launchtest_ros |
| 22 | +import launch |
| 23 | +import launch_ros |
| 24 | +import launch_ros.actions |
| 25 | +import rclpy |
| 26 | +import rclpy.context |
| 27 | +import rclpy.executors |
| 28 | +import std_msgs.msg |
| 29 | + |
| 30 | + |
| 31 | +def generate_test_description(ready_fn): |
| 32 | + # Necessary to get real-time stdout from python processes: |
| 33 | + proc_env = os.environ.copy() |
| 34 | + proc_env['PYTHONUNBUFFERED'] = '1' |
| 35 | + |
| 36 | + # Normally, talker publishes on the 'chatter' topic and listener listens on the |
| 37 | + # 'chatter' topic, but we want to show how to use remappings to munge the data so we |
| 38 | + # will remap these topics when we launch the nodes and insert our own node that can |
| 39 | + # change the data as it passes through |
| 40 | + talker_node = launch_ros.actions.Node( |
| 41 | + package='demo_nodes_py', |
| 42 | + node_executable='talker', |
| 43 | + env=proc_env, |
| 44 | + remappings=[('chatter', 'talker_chatter')], |
| 45 | + ) |
| 46 | + |
| 47 | + listener_node = launch_ros.actions.Node( |
| 48 | + package='demo_nodes_py', |
| 49 | + node_executable='listener', |
| 50 | + env=proc_env, |
| 51 | + ) |
| 52 | + |
| 53 | + return ( |
| 54 | + launch.LaunchDescription([ |
| 55 | + talker_node, |
| 56 | + listener_node, |
| 57 | + # Start tests right away - no need to wait for anything |
| 58 | + launch.actions.OpaqueFunction(function=lambda context: ready_fn()), |
| 59 | + ]), |
| 60 | + { |
| 61 | + 'talker': talker_node, |
| 62 | + 'listener': listener_node, |
| 63 | + } |
| 64 | + ) |
| 65 | + |
| 66 | + |
| 67 | +class TestTalkerListenerLink(unittest.TestCase): |
| 68 | + |
| 69 | + @classmethod |
| 70 | + def setUpClass(cls, proc_output, listener): |
| 71 | + cls.context = rclpy.context.Context() |
| 72 | + rclpy.init(context=cls.context) |
| 73 | + cls.node = rclpy.create_node('test_node', context=cls.context) |
| 74 | + |
| 75 | + # The demo node listener has no synchronization to indicate when it's ready to start |
| 76 | + # receiving messages on the /chatter topic. This plumb_listener method will attempt |
| 77 | + # to publish for a few seconds until it sees output |
| 78 | + publisher = cls.node.create_publisher( |
| 79 | + std_msgs.msg.String, |
| 80 | + 'chatter' |
| 81 | + ) |
| 82 | + msg = std_msgs.msg.String() |
| 83 | + msg.data = 'test message {}'.format(uuid.uuid4()) |
| 84 | + for _ in range(5): |
| 85 | + try: |
| 86 | + publisher.publish(msg) |
| 87 | + proc_output.assertWaitFor( |
| 88 | + msg=msg.data, |
| 89 | + process=listener, |
| 90 | + timeout=1.0 |
| 91 | + ) |
| 92 | + except AssertionError: |
| 93 | + continue |
| 94 | + except NoMatchingProcessException: |
| 95 | + continue |
| 96 | + else: |
| 97 | + return |
| 98 | + else: |
| 99 | + assert False, 'Failed to plumb chatter topic to listener process' |
| 100 | + |
| 101 | + @classmethod |
| 102 | + def tearDownClass(cls): |
| 103 | + cls.node.destroy_node() |
| 104 | + |
| 105 | + def spin_rclpy(self, timeout_sec): |
| 106 | + executor = rclpy.executors.SingleThreadedExecutor(context=self.context) |
| 107 | + executor.add_node(self.node) |
| 108 | + try: |
| 109 | + executor.spin_once(timeout_sec=timeout_sec) |
| 110 | + finally: |
| 111 | + executor.remove_node(self.node) |
| 112 | + |
| 113 | + def test_talker_transmits(self, talker): |
| 114 | + # Expect the talker to publish strings on '/talker_chatter' and also write to stdout |
| 115 | + msgs_rx = [] |
| 116 | + sub = self.node.create_subscription( |
| 117 | + std_msgs.msg.String, |
| 118 | + 'talker_chatter', |
| 119 | + callback=lambda msg: msgs_rx.append(msg) |
| 120 | + ) |
| 121 | + self.addCleanup(self.node.destroy_subscription, sub) |
| 122 | + |
| 123 | + # Wait until the talker transmits two messages over the ROS topic |
| 124 | + end_time = time.time() + 10 |
| 125 | + while time.time() < end_time: |
| 126 | + self.spin_rclpy(1.0) |
| 127 | + if len(msgs_rx) > 2: |
| 128 | + break |
| 129 | + |
| 130 | + self.assertGreater(len(msgs_rx), 2) |
| 131 | + |
| 132 | + # Make sure the talker also output the same data via stdout |
| 133 | + for txt in [msg.data for msg in msgs_rx]: |
| 134 | + self.proc_output.assertWaitFor( |
| 135 | + msg=txt, |
| 136 | + process=talker |
| 137 | + ) |
| 138 | + |
| 139 | + def test_listener_receives(self, listener): |
| 140 | + pub = self.node.create_publisher( |
| 141 | + std_msgs.msg.String, |
| 142 | + 'chatter' |
| 143 | + ) |
| 144 | + self.addCleanup(self.node.destroy_publisher, pub) |
| 145 | + |
| 146 | + # Publish some unique messages on /chatter and verify that the listener gets them |
| 147 | + # and prints them |
| 148 | + for _ in range(5): |
| 149 | + msg = std_msgs.msg.String() |
| 150 | + msg.data = str(uuid.uuid4()) |
| 151 | + |
| 152 | + pub.publish(msg) |
| 153 | + self.proc_output.assertWaitFor( |
| 154 | + msg=msg.data, |
| 155 | + process=listener |
| 156 | + ) |
| 157 | + |
| 158 | + def test_fuzzy_data(self, listener): |
| 159 | + # This test shows how to insert a node in between the talker and the listener to |
| 160 | + # change the data. Here we're going to change 'Hello World' to 'Aloha World' |
| 161 | + def data_mangler(msg): |
| 162 | + msg.data = msg.data.replace('Hello', 'Aloha') |
| 163 | + return msg |
| 164 | + |
| 165 | + republisher = apex_launchtest_ros.DataRepublisher( |
| 166 | + self.node, |
| 167 | + 'talker_chatter', |
| 168 | + 'chatter', |
| 169 | + std_msgs.msg.String, |
| 170 | + data_mangler |
| 171 | + ) |
| 172 | + self.addCleanup(republisher.shutdown) |
| 173 | + |
| 174 | + # Spin for a few seconds until we've republished some mangled messages |
| 175 | + end_time = time.time() + 10 |
| 176 | + while time.time() < end_time: |
| 177 | + self.spin_rclpy(1.0) |
| 178 | + if republisher.get_num_republished() > 2: |
| 179 | + break |
| 180 | + |
| 181 | + self.assertGreater(republisher.get_num_republished(), 2) |
| 182 | + |
| 183 | + # Sanity check that we're changing 'Hello World' |
| 184 | + self.proc_output.assertWaitFor('Aloha World') |
| 185 | + |
| 186 | + # Check for the actual messages we sent |
| 187 | + for msg in republisher.get_republished(): |
| 188 | + self.proc_output.assertWaitFor(msg.data, listener) |
0 commit comments