Skip to content

Commit 13a8d16

Browse files
committed
--atomic flag for load & set
Signed-off-by: Brian Chen <[email protected]>
1 parent 81ca3bb commit 13a8d16

File tree

4 files changed

+86
-5
lines changed

4 files changed

+86
-5
lines changed

ros2param/ros2param/api/__init__.py

Lines changed: 36 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,10 @@ def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
4949
parameters = list(parameter_dict_from_yaml_file(parameter_file, use_wildcard).values())
5050
rclpy.spin_until_future_complete(node, future)
5151
response = future.result()
52+
if response is None:
53+
raise RuntimeError('Exception while calling service of node '
54+
f'{node_name}: {future.exception()}')
55+
5256
assert len(response.results) == len(parameters), 'Not all parameters set'
5357
for i in range(0, len(response.results)):
5458
result = response.results[i]
@@ -65,6 +69,26 @@ def load_parameter_file(*, node, node_name, parameter_file, use_wildcard):
6569
print(msg, file=sys.stderr)
6670

6771

72+
def load_parameter_file_atomically(*, node, node_name, parameter_file, use_wildcard):
73+
client = AsyncParameterClient(node, node_name)
74+
ready = client.wait_for_services(timeout_sec=5.0)
75+
if not ready:
76+
raise RuntimeError('Wait for service timed out')
77+
future = client.load_parameter_file_atomically(parameter_file, use_wildcard)
78+
parameters = list(parameter_dict_from_yaml_file(parameter_file, use_wildcard).values())
79+
rclpy.spin_until_future_complete(node, future)
80+
response = future.result()
81+
if response is None:
82+
raise RuntimeError('Exception while calling service of node '
83+
f'{node_name}: {future.exception()}')
84+
85+
if response.result.successful:
86+
msg = 'Set parameters {} successful'.format(' '.join([i.name for i in parameters]))
87+
if response.result.reason:
88+
msg += ': ' + response.result.reason
89+
print(msg)
90+
91+
6892
def call_describe_parameters(*, node, node_name, parameter_names=None):
6993
client = AsyncParameterClient(node, node_name)
7094
ready = client.wait_for_services(timeout_sec=5.0)
@@ -93,6 +117,18 @@ def call_get_parameters(*, node, node_name, parameter_names):
93117
return response
94118

95119

120+
def call_set_parameters_atomically(*, node, node_name, parameters):
121+
client = AsyncParameterClient(node, node_name)
122+
client.wait_for_services(timeout_sec=5.0)
123+
future = client.set_parameters_atomically(parameters)
124+
rclpy.spin_until_future_complete(node, future)
125+
response = future.result()
126+
if response is None:
127+
raise RuntimeError('Exception while calling service of node '
128+
f'{node_name}: {future.exception()}')
129+
return response
130+
131+
96132
def call_set_parameters(*, node, node_name, parameters):
97133
client = AsyncParameterClient(node, node_name)
98134
ready = client.wait_for_services(timeout_sec=5.0)

ros2param/ros2param/verb/load.py

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
from ros2node.api import get_node_names
2020
from ros2node.api import NodeNameCompleter
2121
from ros2param.api import load_parameter_file
22+
from ros2param.api import load_parameter_file_atomically
2223
from ros2param.verb import VerbExtension
2324

2425

@@ -39,6 +40,9 @@ def add_arguments(self, parser, cli_name): # noqa: D102
3940
parser.add_argument(
4041
'--no-use-wildcard', action='store_true',
4142
help="Do not load parameters in the '/**' namespace into the node")
43+
parser.add_argument(
44+
'--atomic', action='store_true',
45+
help='Load parameters atomically')
4246

4347
def main(self, *, args): # noqa: D102
4448
with NodeStrategy(args) as node:
@@ -50,5 +54,11 @@ def main(self, *, args): # noqa: D102
5054
return 'Node not found'
5155

5256
with DirectNode(args) as node:
53-
load_parameter_file(node=node, node_name=node_name, parameter_file=args.parameter_file,
54-
use_wildcard=not args.no_use_wildcard)
57+
if args.atomic:
58+
load_parameter_file_atomically(node=node, node_name=node_name,
59+
parameter_file=args.parameter_file,
60+
use_wildcard=not args.no_use_wildcard)
61+
else:
62+
load_parameter_file(node=node, node_name=node_name,
63+
parameter_file=args.parameter_file,
64+
use_wildcard=not args.no_use_wildcard)

ros2param/ros2param/verb/set.py

Lines changed: 13 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@
2424
from ros2node.api import NodeNameCompleter
2525

2626
from ros2param.api import call_set_parameters
27+
from ros2param.api import call_set_parameters_atomically
2728
from ros2param.api import ParameterNameCompleter
2829
from ros2param.verb import VerbExtension
2930

@@ -47,6 +48,10 @@ def add_arguments(self, parser, cli_name): # noqa: D102
4748
'--include-hidden-nodes', action='store_true',
4849
help='Consider hidden nodes as well')
4950

51+
parser.add_argument(
52+
'--atomic', action='store_true',
53+
help='Set parameters atomically')
54+
5055
def build_parameters(self, params):
5156
parameters = []
5257
if len(params) % 2:
@@ -72,9 +77,14 @@ def main(self, *, args): # noqa: D102
7277

7378
with DirectNode(args) as node:
7479
parameters = self.build_parameters(args.parameters)
75-
response = call_set_parameters(
76-
node=node, node_name=args.node_name, parameters=parameters)
77-
results = response.results
80+
if args.atomic:
81+
response = call_set_parameters_atomically(node=node, node_name=args.node_name,
82+
parameters=parameters)
83+
results = [response.result]
84+
else:
85+
response = call_set_parameters(node=node, node_name=args.node_name,
86+
parameters=parameters)
87+
results = response.results
7888

7989
for result in results:
8090
if result.successful:

ros2param/test/test_verb_load.py

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -294,6 +294,31 @@ def test_verb_load(self):
294294
strict=True
295295
)
296296

297+
def test_verb_load_atomic(self):
298+
with tempfile.TemporaryDirectory() as tmpdir:
299+
filepath = self._write_param_file(tmpdir, 'params.yaml')
300+
with self.launch_param_load_command(
301+
arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}', filepath, '--atomic']
302+
) as param_load_command:
303+
assert param_load_command.wait_for_shutdown(timeout=TEST_TIMEOUT)
304+
assert param_load_command.exit_code == launch_testing.asserts.EXIT_OK
305+
assert launch_testing.tools.expect_output(
306+
expected_lines=[''],
307+
text=param_load_command.output,
308+
strict=True
309+
)
310+
# Dump with ros2 param dump and compare that output matches input file
311+
with self.launch_param_dump_command(
312+
arguments=[f'{TEST_NAMESPACE}/{TEST_NODE}']
313+
) as param_dump_command:
314+
assert param_dump_command.wait_for_shutdown(timeout=TEST_TIMEOUT)
315+
assert param_dump_command.exit_code == launch_testing.asserts.EXIT_OK
316+
assert launch_testing.tools.expect_output(
317+
expected_text=INPUT_PARAMETER_FILE + '\n',
318+
text=param_dump_command.output,
319+
strict=True
320+
)
321+
297322
def test_verb_load_wildcard(self):
298323
with tempfile.TemporaryDirectory() as tmpdir:
299324
# Try param file with only wildcard

0 commit comments

Comments
 (0)