|
13 | 13 | # limitations under the License. |
14 | 14 |
|
15 | 15 | import platform |
| 16 | +import threading |
16 | 17 | import time |
| 18 | +import traceback |
17 | 19 | import unittest |
18 | 20 |
|
19 | 21 | from rcl_interfaces.srv import GetParameters |
20 | 22 | import rclpy |
21 | 23 | import rclpy.executors |
| 24 | +import rclpy.node |
22 | 25 | from rclpy.utilities import get_rmw_implementation_identifier |
23 | 26 | from test_msgs.srv import Empty |
24 | 27 |
|
@@ -56,6 +59,21 @@ def do_test_service_name(cls, test_service_name_list): |
56 | 59 | client.destroy() |
57 | 60 | node.destroy_node() |
58 | 61 |
|
| 62 | + @staticmethod |
| 63 | + def _spin_rclpy_node( |
| 64 | + rclpy_node: rclpy.node.Node, |
| 65 | + rclpy_executor: rclpy.executors.SingleThreadedExecutor |
| 66 | + ) -> None: |
| 67 | + try: |
| 68 | + rclpy_executor.spin() |
| 69 | + except rclpy.executors.ExternalShutdownException: |
| 70 | + pass |
| 71 | + except Exception as err: |
| 72 | + traceback.print_exc() |
| 73 | + print(rclpy_node.get_name() + ': ' + str(err)) |
| 74 | + print(rclpy_node.get_name() + ': rclpy_node exit') |
| 75 | +# rclpy_node.destroy_node() |
| 76 | + |
59 | 77 | def test_wait_for_service_5sec(self): |
60 | 78 | cli = self.node.create_client(GetParameters, 'get/parameters') |
61 | 79 | try: |
@@ -183,6 +201,47 @@ def test_get_service_name_after_remapping(self): |
183 | 201 | ] |
184 | 202 | TestClient.do_test_service_name(test_service_name_list) |
185 | 203 |
|
| 204 | + def test_sync_call(self): |
| 205 | + def _service(request, response): |
| 206 | + return response |
| 207 | + cli = self.node.create_client(GetParameters, 'get/parameters') |
| 208 | + srv = self.node.create_service(GetParameters, 'get/parameters', _service) |
| 209 | + try: |
| 210 | + self.assertTrue(cli.wait_for_service(timeout_sec=20)) |
| 211 | + executor = rclpy.executors.SingleThreadedExecutor(context=self.context) |
| 212 | + executor.add_node(self.node) |
| 213 | + executor_thread = threading.Thread( |
| 214 | + target=TestClient._spin_rclpy_node, args=(self.node, executor)) |
| 215 | + executor_thread.start() |
| 216 | + result = cli.call(GetParameters.Request(), 0.5) |
| 217 | + self.assertTrue(result is not None) |
| 218 | + executor.shutdown() |
| 219 | + executor_thread.join() |
| 220 | + finally: |
| 221 | + self.node.destroy_client(cli) |
| 222 | + self.node.destroy_service(srv) |
| 223 | + |
| 224 | + def test_sync_call_timeout(self): |
| 225 | + def _service(request, response): |
| 226 | + time.sleep(1) |
| 227 | + return response |
| 228 | + cli = self.node.create_client(GetParameters, 'get/parameters') |
| 229 | + srv = self.node.create_service(GetParameters, 'get/parameters', _service) |
| 230 | + try: |
| 231 | + self.assertTrue(cli.wait_for_service(timeout_sec=20)) |
| 232 | + executor = rclpy.executors.SingleThreadedExecutor(context=self.context) |
| 233 | + executor.add_node(self.node) |
| 234 | + executor_thread = threading.Thread( |
| 235 | + target=TestClient._spin_rclpy_node, args=(self.node, executor)) |
| 236 | + executor_thread.start() |
| 237 | + result = cli.call(GetParameters.Request(), 0.5) |
| 238 | + self.assertTrue(result is None) |
| 239 | + executor.shutdown() |
| 240 | + executor_thread.join() |
| 241 | + finally: |
| 242 | + self.node.destroy_client(cli) |
| 243 | + self.node.destroy_service(srv) |
| 244 | + |
186 | 245 |
|
187 | 246 | if __name__ == '__main__': |
188 | 247 | unittest.main() |
0 commit comments