Skip to content

Commit fc02ffe

Browse files
refactor: make ros2param use rclpy.parameter_client (#716)
Refactors ros2param to use rclpy.parameter_client (ros2/rclpy@3053a8a). Co-authored-by: Jacob Perron <[email protected]> Signed-off-by: Brian Chen <[email protected]>
1 parent c7d3204 commit fc02ffe

File tree

6 files changed

+96
-252
lines changed

6 files changed

+96
-252
lines changed

ros2param/ros2param/api/__init__.py

Lines changed: 55 additions & 170 deletions
Original file line numberDiff line numberDiff line change
@@ -13,113 +13,44 @@
1313
# limitations under the License.
1414

1515
import sys
16+
import warnings
1617

17-
from rcl_interfaces.msg import Parameter
1818
from rcl_interfaces.msg import ParameterType
19-
from rcl_interfaces.msg import ParameterValue
20-
from rcl_interfaces.srv import DescribeParameters
21-
from rcl_interfaces.srv import GetParameters
22-
from rcl_interfaces.srv import ListParameters
23-
from rcl_interfaces.srv import SetParameters
2419
import rclpy
25-
from rclpy.parameter import PARAMETER_SEPARATOR_STRING
20+
from rclpy.parameter import get_parameter_value as rclpy_get_parameter_value
21+
from rclpy.parameter import parameter_dict_from_yaml_file
22+
from rclpy.parameter import parameter_value_to_python
23+
from rclpy.parameter_client import AsyncParameterClient
2624
from ros2cli.node.direct import DirectNode
2725

28-
import yaml
26+
27+
def get_parameter_value(*, string_value):
28+
warnings.warn('get_parameter_value() is deprecated. '
29+
'Use rclpy.parameter.get_parameter_value instead')
30+
return rclpy_get_parameter_value(string_value)
2931

3032

3133
def get_value(*, parameter_value):
3234
"""Get the value from a ParameterValue."""
33-
if parameter_value.type == ParameterType.PARAMETER_BOOL:
34-
value = parameter_value.bool_value
35-
elif parameter_value.type == ParameterType.PARAMETER_INTEGER:
36-
value = parameter_value.integer_value
37-
elif parameter_value.type == ParameterType.PARAMETER_DOUBLE:
38-
value = parameter_value.double_value
39-
elif parameter_value.type == ParameterType.PARAMETER_STRING:
40-
value = parameter_value.string_value
41-
elif parameter_value.type == ParameterType.PARAMETER_BYTE_ARRAY:
42-
value = list(parameter_value.byte_array_value)
43-
elif parameter_value.type == ParameterType.PARAMETER_BOOL_ARRAY:
44-
value = list(parameter_value.bool_array_value)
45-
elif parameter_value.type == ParameterType.PARAMETER_INTEGER_ARRAY:
46-
value = list(parameter_value.integer_array_value)
47-
elif parameter_value.type == ParameterType.PARAMETER_DOUBLE_ARRAY:
48-
value = list(parameter_value.double_array_value)
49-
elif parameter_value.type == ParameterType.PARAMETER_STRING_ARRAY:
50-
value = list(parameter_value.string_array_value)
51-
elif parameter_value.type == ParameterType.PARAMETER_NOT_SET:
52-
value = None
53-
else:
54-
value = None
55-
56-
return value
57-
58-
59-
def get_parameter_value(*, string_value):
60-
"""Guess the desired type of the parameter based on the string value."""
61-
value = ParameterValue()
35+
value = None
6236
try:
63-
yaml_value = yaml.safe_load(string_value)
64-
except yaml.parser.ParserError:
65-
yaml_value = string_value
66-
67-
if isinstance(yaml_value, bool):
68-
value.type = ParameterType.PARAMETER_BOOL
69-
value.bool_value = yaml_value
70-
elif isinstance(yaml_value, int):
71-
value.type = ParameterType.PARAMETER_INTEGER
72-
value.integer_value = yaml_value
73-
elif isinstance(yaml_value, float):
74-
value.type = ParameterType.PARAMETER_DOUBLE
75-
value.double_value = yaml_value
76-
elif isinstance(yaml_value, list):
77-
if all((isinstance(v, bool) for v in yaml_value)):
78-
value.type = ParameterType.PARAMETER_BOOL_ARRAY
79-
value.bool_array_value = yaml_value
80-
elif all((isinstance(v, int) for v in yaml_value)):
81-
value.type = ParameterType.PARAMETER_INTEGER_ARRAY
82-
value.integer_array_value = yaml_value
83-
elif all((isinstance(v, float) for v in yaml_value)):
84-
value.type = ParameterType.PARAMETER_DOUBLE_ARRAY
85-
value.double_array_value = yaml_value
86-
elif all((isinstance(v, str) for v in yaml_value)):
87-
value.type = ParameterType.PARAMETER_STRING_ARRAY
88-
value.string_array_value = yaml_value
89-
else:
90-
value.type = ParameterType.PARAMETER_STRING
91-
value.string_value = string_value
92-
else:
93-
value.type = ParameterType.PARAMETER_STRING
94-
value.string_value = yaml_value
37+
value = parameter_value_to_python(parameter_value)
38+
except RuntimeError as e:
39+
print(f'Runtime error {e} raised')
9540
return value
9641

9742

98-
def parse_parameter_dict(*, namespace, parameter_dict):
99-
parameters = []
100-
for param_name, param_value in parameter_dict.items():
101-
full_param_name = namespace + param_name
102-
# Unroll nested parameters
103-
if type(param_value) == dict:
104-
parameters += parse_parameter_dict(
105-
namespace=full_param_name + PARAMETER_SEPARATOR_STRING,
106-
parameter_dict=param_value)
107-
else:
108-
parameter = Parameter()
109-
parameter.name = full_param_name
110-
parameter.value = get_parameter_value(string_value=str(param_value))
111-
parameters.append(parameter)
112-
return parameters
113-
114-
115-
def load_parameter_dict(*, node, node_name, parameter_dict):
116-
117-
parameters = parse_parameter_dict(namespace='', parameter_dict=parameter_dict)
118-
response = call_set_parameters(
119-
node=node, node_name=node_name, parameters=parameters)
120-
121-
# output response
122-
assert len(response.results) == len(parameters)
43+
def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
44+
client = AsyncParameterClient(node, node_name)
45+
ready = client.wait_for_services(timeout_sec=5.0)
46+
if not ready:
47+
raise RuntimeError('Wait for service timed out waiting for '
48+
f'parameter services for node {node_name}')
49+
future = client.load_parameter_file(parameter_file, use_wildcard)
50+
parameters = list(parameter_dict_from_yaml_file(parameter_file, use_wildcard).values())
51+
rclpy.spin_until_future_complete(node, future)
52+
response = future.result()
53+
assert len(response.results) == len(parameters), 'Not all parameters set'
12354
for i in range(0, len(response.results)):
12455
result = response.results[i]
12556
param_name = parameters[i].name
@@ -135,105 +66,59 @@ def load_parameter_dict(*, node, node_name, parameter_dict):
13566
print(msg, file=sys.stderr)
13667

13768

138-
def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
139-
# Remove leading slash and namespaces
140-
with open(parameter_file, 'r') as f:
141-
param_file = yaml.safe_load(f)
142-
param_keys = []
143-
if use_wildcard and '/**' in param_file:
144-
param_keys.append('/**')
145-
if node_name in param_file:
146-
param_keys.append(node_name)
147-
148-
if param_keys == []:
149-
raise RuntimeError('Param file does not contain parameters for {}, '
150-
' only for nodes: {}' .format(node_name, param_file.keys()))
151-
param_dict = {}
152-
for k in param_keys:
153-
value = param_file[k]
154-
if type(value) != dict or 'ros__parameters' not in value:
155-
raise RuntimeError('Invalid structure of parameter file for node {}'
156-
'expected same format as provided by ros2 param dump'
157-
.format(k))
158-
param_dict.update(value['ros__parameters'])
159-
load_parameter_dict(node=node, node_name=node_name, parameter_dict=param_dict)
160-
161-
16269
def call_describe_parameters(*, node, node_name, parameter_names=None):
163-
# create client
164-
client = node.create_client(
165-
DescribeParameters, f'{node_name}/describe_parameters')
166-
167-
# call as soon as ready
168-
ready = client.wait_for_service(timeout_sec=5.0)
70+
client = AsyncParameterClient(node, node_name)
71+
ready = client.wait_for_services(timeout_sec=5.0)
16972
if not ready:
170-
raise RuntimeError('Wait for service timed out')
171-
172-
request = DescribeParameters.Request()
173-
if parameter_names:
174-
request.names = parameter_names
175-
future = client.call_async(request)
73+
raise RuntimeError('Wait for service timed out waiting for '
74+
f'parameter services for node {node_name}')
75+
future = client.describe_parameters(parameter_names)
17676
rclpy.spin_until_future_complete(node, future)
177-
178-
# handle response
17977
response = future.result()
78+
if response is None:
79+
raise RuntimeError('Exception while calling service of node '
80+
f'{node_name}: {future.exception()}')
18081
return response
18182

18283

18384
def call_get_parameters(*, node, node_name, parameter_names):
184-
# create client
185-
client = node.create_client(GetParameters, f'{node_name}/get_parameters')
186-
187-
# call as soon as ready
188-
ready = client.wait_for_service(timeout_sec=5.0)
85+
client = AsyncParameterClient(node, node_name)
86+
ready = client.wait_for_services(timeout_sec=5.0)
18987
if not ready:
190-
raise RuntimeError('Wait for service timed out')
191-
192-
request = GetParameters.Request()
193-
request.names = parameter_names
194-
future = client.call_async(request)
88+
raise RuntimeError('Wait for service timed out waiting for '
89+
f'parameter services for node {node_name}')
90+
future = client.get_parameters(parameter_names)
19591
rclpy.spin_until_future_complete(node, future)
196-
197-
# handle response
19892
response = future.result()
93+
if response is None:
94+
raise RuntimeError('Exception while calling service of node '
95+
f'{node_name}: {future.exception()}')
19996
return response
20097

20198

20299
def call_set_parameters(*, node, node_name, parameters):
203-
# create client
204-
client = node.create_client(SetParameters, f'{node_name}/set_parameters')
205-
206-
# call as soon as ready
207-
ready = client.wait_for_service(timeout_sec=5.0)
100+
client = AsyncParameterClient(node, node_name)
101+
ready = client.wait_for_services(timeout_sec=5.0)
208102
if not ready:
209-
raise RuntimeError('Wait for service timed out')
210-
211-
request = SetParameters.Request()
212-
request.parameters = parameters
213-
future = client.call_async(request)
103+
raise RuntimeError('Wait for service timed out waiting for '
104+
f'parameter services for node {node_name}')
105+
future = client.set_parameters(parameters)
214106
rclpy.spin_until_future_complete(node, future)
215-
216-
# handle response
217107
response = future.result()
108+
if response is None:
109+
raise RuntimeError('Exception while calling service of node '
110+
f'{node_name}: {future.exception()}')
218111
return response
219112

220113

221-
def call_list_parameters(*, node, node_name, prefix=None):
222-
# create client
223-
client = node.create_client(ListParameters, f'{node_name}/list_parameters')
224-
225-
# call as soon as ready
226-
ready = client.wait_for_service(timeout_sec=5.0)
114+
def call_list_parameters(*, node, node_name, prefixes=None):
115+
client = AsyncParameterClient(node, node_name)
116+
ready = client.wait_for_services(timeout_sec=5.0)
227117
if not ready:
228-
raise RuntimeError('Wait for service timed out')
229-
230-
request = ListParameters.Request()
231-
future = client.call_async(request)
118+
return None
119+
future = client.list_parameters(prefixes=prefixes)
232120
rclpy.spin_until_future_complete(node, future)
233-
234-
# handle response
235-
response = future.result()
236-
return response.result.names
121+
return future
237122

238123

239124
def get_parameter_type_string(parameter_type):

ros2param/ros2param/verb/dump.py

Lines changed: 19 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -15,24 +15,19 @@
1515
import os
1616
import sys
1717

18-
from rcl_interfaces.srv import ListParameters
19-
20-
import rclpy
2118
from rclpy.parameter import PARAMETER_SEPARATOR_STRING
22-
2319
from ros2cli.node.direct import DirectNode
2420
from ros2cli.node.strategy import add_arguments
2521
from ros2cli.node.strategy import NodeStrategy
26-
2722
from ros2node.api import get_absolute_node_name
2823
from ros2node.api import get_node_names
2924
from ros2node.api import NodeNameCompleter
3025
from ros2node.api import parse_node_name
3126

3227
from ros2param.api import call_get_parameters
28+
from ros2param.api import call_list_parameters
3329
from ros2param.api import get_value
3430
from ros2param.verb import VerbExtension
35-
3631
import yaml
3732

3833

@@ -57,17 +52,17 @@ def add_arguments(self, parser, cli_name): # noqa: D102
5752
help='DEPRECATED: Does nothing.')
5853

5954
@staticmethod
60-
def get_parameter_value(node, node_name, param):
55+
def get_parameter_values(node, node_name, params):
6156
response = call_get_parameters(
6257
node=node, node_name=node_name,
63-
parameter_names=[param])
58+
parameter_names=params)
6459

6560
# requested parameter not set
6661
if not response.values:
6762
return '# Parameter not set'
6863

6964
# extract type specific value
70-
return get_value(parameter_value=response.values[0])
65+
return [get_value(parameter_value=i) for i in response.values]
7166

7267
def insert_dict(self, dictionary, key, value):
7368
split = key.split(PARAMETER_SEPARATOR_STRING, 1)
@@ -94,36 +89,28 @@ def main(self, *, args): # noqa: D102
9489
f"'{args.output_dir}' is not a valid directory.")
9590

9691
with DirectNode(args) as node:
97-
# create client
98-
service_name = f'{absolute_node_name}/list_parameters'
99-
client = node.create_client(ListParameters, service_name)
100-
101-
client.wait_for_service()
102-
103-
if not client.service_is_ready():
104-
raise RuntimeError(f"Could not reach service '{service_name}'")
105-
106-
request = ListParameters.Request()
107-
future = client.call_async(request)
108-
109-
# wait for response
110-
rclpy.spin_until_future_complete(node, future)
111-
11292
yaml_output = {node_name.full_name: {'ros__parameters': {}}}
11393

11494
# retrieve values
115-
if future.result() is not None:
116-
response = future.result()
117-
for param_name in sorted(response.result.names):
118-
pval = self.get_parameter_value(node, absolute_node_name, param_name)
119-
self.insert_dict(
120-
yaml_output[node_name.full_name]['ros__parameters'], param_name, pval)
121-
else:
122-
e = future.exception()
95+
response = call_list_parameters(node=node, node_name=absolute_node_name)
96+
if response is None:
97+
raise RuntimeError(
98+
'Wait for service timed out waiting for '
99+
f'parameter services for node {node_name.full_name}')
100+
elif response.result() is None:
101+
e = response.exception()
123102
raise RuntimeError(
124103
'Exception while calling service of node '
125104
f"'{node_name.full_name}': {e}")
126105

106+
response = response.result().result.names
107+
response = sorted(response)
108+
parameter_values = self.get_parameter_values(node, absolute_node_name, response)
109+
110+
for param_name, pval in zip(response, parameter_values):
111+
self.insert_dict(
112+
yaml_output[node_name.full_name]['ros__parameters'], param_name, pval)
113+
127114
if args.print:
128115
print(
129116
"WARNING: '--print' is deprecated; this utility prints to stdout by default",

0 commit comments

Comments
 (0)