Skip to content

Commit 4d6463b

Browse files
committed
fix tests
Signed-off-by: Brian Chen <[email protected]>
1 parent b7182c9 commit 4d6463b

File tree

4 files changed

+44
-39
lines changed

4 files changed

+44
-39
lines changed

ros2param/ros2param/api/__init__.py

Lines changed: 35 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
# limitations under the License.
1414

1515
import sys
16+
import time
1617
import warnings
1718

1819
from rcl_interfaces.msg import ParameterType
@@ -40,13 +41,20 @@ def get_value(*, parameter_value):
4041
return value
4142

4243

43-
def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
44-
# Remove leading slash and namespaces
45-
client = AsyncParameterClient(node, node_name)
46-
client.wait_for_services(timeout_sec=5.0)
44+
def busy_wait_client(client, node):
45+
timeout_sec = 5
46+
prev = time.time()
47+
while not (client.services_are_ready() or timeout_sec < 0):
48+
client.wait_for_services(timeout_sec=0.1)
49+
rclpy.spin_once(node)
50+
timeout_sec -= prev - time.time()
4751
if not client.services_are_ready():
4852
raise RuntimeError('Could not reach parameter services')
4953

54+
55+
def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
56+
client = AsyncParameterClient(node, node_name)
57+
busy_wait_client(client, node)
5058
future = client.load_parameter_file(parameter_file, use_wildcard)
5159
parameters = list(parameter_dict_from_yaml_file(parameter_file, use_wildcard).values())
5260
rclpy.spin_until_future_complete(node, future)
@@ -69,45 +77,53 @@ def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
6977

7078
def call_describe_parameters(*, node, node_name, parameter_names=None):
7179
client = AsyncParameterClient(node, node_name)
72-
client.wait_for_services(timeout_sec=5.0)
73-
if not client.services_are_ready():
74-
raise RuntimeError('Could not reach parameter services')
80+
busy_wait_client(client, node)
81+
7582
future = client.describe_parameters(parameter_names)
7683
rclpy.spin_until_future_complete(node, future)
7784
response = future.result()
85+
if response is None:
86+
raise RuntimeError('Exception while calling service of node '
87+
f'{node_name}: {future.exception()}')
7888
return response
7989

8090

8191
def call_get_parameters(*, node, node_name, parameter_names):
8292
client = AsyncParameterClient(node, node_name)
83-
client.wait_for_services(timeout_sec=5.0)
84-
if not client.services_are_ready():
85-
raise RuntimeError('Could not reach parameter services')
93+
busy_wait_client(client, node)
94+
8695
future = client.get_parameters(parameter_names)
8796
rclpy.spin_until_future_complete(node, future)
8897
response = future.result()
98+
if response is None:
99+
raise RuntimeError('Exception while calling service of node '
100+
f'{node_name}: {future.exception()}')
89101
return response
90102

91103

92104
def call_set_parameters(*, node, node_name, parameters):
93105
client = AsyncParameterClient(node, node_name)
94-
client.wait_for_services(timeout_sec=5.0)
95-
if not client.services_are_ready():
96-
raise RuntimeError('Could not reach parameter services')
106+
busy_wait_client(client, node)
107+
97108
future = client.set_parameters(parameters)
98109
rclpy.spin_until_future_complete(node, future)
99110
response = future.result()
111+
if response is None:
112+
raise RuntimeError('Exception while calling service of node '
113+
f'{node_name}: {future.exception()}')
100114
return response
101115

102116

103-
def call_list_parameters(*, node, node_name):
117+
def call_list_parameters(*, node, node_name, prefixes=None):
104118
client = AsyncParameterClient(node, node_name)
105-
client.wait_for_services(timeout_sec=5.0)
106-
if not client.services_are_ready():
107-
raise RuntimeError('Could not reach parameter services')
108-
future = client.list_parameters()
109-
rclpy.spin_until_future_complete(node, future) # This is hanging..
119+
busy_wait_client(client, node)
120+
121+
future = client.list_parameters(prefixes=prefixes)
122+
rclpy.spin_until_future_complete(node, future)
110123
response = future.result()
124+
if response is None:
125+
raise RuntimeError('Exception while calling service of node '
126+
f'{node_name}: {future.exception()}')
111127
return response.result.names
112128

113129

ros2param/ros2param/verb/dump.py

Lines changed: 4 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -15,8 +15,6 @@
1515
import os
1616
import sys
1717

18-
from rcl_interfaces.srv import ListParameters
19-
import rclpy
2018
from rclpy.parameter import PARAMETER_SEPARATOR_STRING
2119
from ros2cli.node.direct import DirectNode
2220
from ros2cli.node.strategy import add_arguments
@@ -96,16 +94,10 @@ def main(self, *, args): # noqa: D102
9694
# retrieve values
9795
response = call_list_parameters(node=node, node_name=absolute_node_name)
9896

99-
if response is not None:
100-
for param_name in sorted(response):
101-
pval = self.get_parameter_value(node, absolute_node_name, param_name)
102-
self.insert_dict(
103-
yaml_output[node_name.full_name]['ros__parameters'], param_name, pval)
104-
else:
105-
e = future.exception()
106-
raise RuntimeError(
107-
'Exception while calling service of node '
108-
f"'{node_name.full_name}': {e}")
97+
for param_name in sorted(response):
98+
pval = self.get_parameter_value(node, absolute_node_name, param_name)
99+
self.insert_dict(
100+
yaml_output[node_name.full_name]['ros__parameters'], param_name, pval)
109101

110102
if args.print:
111103
print(

ros2param/ros2param/verb/list.py

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -15,22 +15,18 @@
1515
import re
1616
import sys
1717

18-
import rclpy
1918
from ros2cli.node.direct import DirectNode
2019
from ros2cli.node.strategy import add_arguments
2120
from ros2cli.node.strategy import NodeStrategy
2221
from ros2node.api import get_absolute_node_name
2322
from ros2node.api import get_node_names
2423
from ros2node.api import NodeNameCompleter
2524

26-
from rcl_interfaces.srv import ListParameters
27-
2825
from ros2param.api import call_describe_parameters
2926
from ros2param.api import call_list_parameters
3027
from ros2param.api import get_parameter_type_string
3128
from ros2param.verb import VerbExtension
3229

33-
from ros2service.api import get_service_names
3430

3531
class ListVerb(VerbExtension):
3632
"""Output a list of available parameters."""
@@ -75,7 +71,9 @@ def main(self, *, args): # noqa: D102
7571
with DirectNode(args) as node:
7672
responses = {}
7773
for node_name in node_names:
78-
responses[node_name] = call_list_parameters(node=node, node_name=node_name.name)
74+
responses[node_name] = call_list_parameters(node=node,
75+
node_name=node_name.full_name,
76+
prefixes=args.param_prefixes)
7977
# print responses
8078
for node_name in sorted(responses.keys()):
8179
response = responses[node_name]

ros2param/test/test_verb_load.py

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,7 @@ def generate_test_description(rmw_implementation):
129129
])
130130

131131

132-
class TestVerbDump(unittest.TestCase):
132+
class TestVerbLoad(unittest.TestCase):
133133

134134
@classmethod
135135
def setUpClass(
@@ -305,8 +305,7 @@ def test_verb_load_wildcard(self):
305305
assert param_load_command.wait_for_shutdown(timeout=TEST_TIMEOUT)
306306
assert param_load_command.exit_code != launch_testing.asserts.EXIT_OK
307307
assert launch_testing.tools.expect_output(
308-
expected_lines=['Param file does not contain parameters for '
309-
f'{TEST_NAMESPACE}/{TEST_NODE}'],
308+
expected_lines=['Param file does not contain selected parameters'],
310309
text=param_load_command.output,
311310
strict=False
312311
)

0 commit comments

Comments
 (0)