Skip to content

Commit

Permalink
[ros2param] Wait for discovery before running tests
Browse files Browse the repository at this point in the history
Fixes #480.

We catch expected exceptions from rclpy (or transitively as xmlrpc.client.Fault) while we wait for discovery in the test setup.

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Apr 9, 2020
1 parent c9e9e2f commit 601f174
Showing 1 changed file with 32 additions and 1 deletion.
33 changes: 32 additions & 1 deletion ros2param/test/test_verb_dump.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,17 +16,22 @@
import os
import tempfile
import threading
import time
import unittest
from unittest.mock import patch
import xmlrpc

import rclpy
from rclpy.executors import MultiThreadedExecutor
from rclpy.parameter import PARAMETER_SEPARATOR_STRING

from ros2cli import cli
from ros2cli.node.strategy import NodeStrategy

TEST_NODE = 'test_node'
TEST_NAMESPACE = 'foo'
TEST_NAMESPACE = '/foo'

TEST_TIMEOUT = 5.0

EXPECTED_PARAMETER_FILE = """\
test_node:
Expand Down Expand Up @@ -77,6 +82,32 @@ def tearDownClass(cls):
rclpy.shutdown(context=cls.context)
cls.exec_thread.join()

def setUp(self):
# Ensure the daemon node is running and discovers the test node
start_time = time.time()
with NodeStrategy(None) as node:
while (time.time() - start_time) < TEST_TIMEOUT:
# TODO(jacobperron): Create a generic 'CliNodeError' so we can treat errors
# from DirectNode and DaemonNode the same
try:
services = node.get_service_names_and_types_by_node(TEST_NODE, TEST_NAMESPACE)
except rclpy.node.NodeNameNonExistentError:
continue
except xmlrpc.client.Fault as e:
if 'NodeNameNonExistentError' in e.faultString:
continue
raise

service_names = [name_type_tuple[0] for name_type_tuple in services]
if (
len(service_names) > 0
and f'{TEST_NAMESPACE}/{TEST_NODE}/get_parameters' in service_names
):
break
delta = time.time() - start_time
if delta >= TEST_TIMEOUT:
self.fail(f'CLI daemon failed to find test node after {delta} seconds')

def _output_file(self):

ns = self.node.get_namespace()
Expand Down

0 comments on commit 601f174

Please sign in to comment.