2424from ros2node .api import wait_for_node
2525
2626from ros2param .api import call_set_parameters
27+ from ros2param .api import call_set_parameters_atomically
2728from ros2param .api import ParameterNameCompleter
2829from ros2param .verb import VerbExtension
2930
3031
32+ class _NameValueCompleter :
33+ """
34+ Completer for interleaved name/value pairs.
35+
36+ Delegates to ParameterNameCompleter for name positions (even index)
37+ and returns no completions for value positions (odd index).
38+ """
39+
40+ def __call__ (self , prefix , parsed_args , ** kwargs ):
41+ already = getattr (parsed_args , 'params_and_values' , None ) or []
42+ # Even count of already-collected tokens → completing a *name*
43+ if len (already ) % 2 == 0 :
44+ return ParameterNameCompleter ()(prefix , parsed_args , ** kwargs )
45+ # Odd count → completing a *value*; no suggestions
46+ return []
47+
48+
3149class SetVerb (VerbExtension ):
3250 """Set parameter."""
3351
@@ -41,38 +59,80 @@ def add_arguments(self, parser, cli_name): # noqa: D102
4159 '--include-hidden-nodes' , action = 'store_true' ,
4260 help = 'Consider hidden nodes as well' )
4361 arg = parser .add_argument (
44- 'parameter_name' , help = 'Name of the parameter' )
45- arg .completer = ParameterNameCompleter ()
62+ 'params_and_values' , nargs = '+' ,
63+ metavar = 'name value' ,
64+ help = 'Parameter name and value pair(s): name value [name value ...]. '
65+ 'Provide one or more name/value pairs to set multiple parameters at once.' )
66+ arg .completer = _NameValueCompleter ()
4667 parser .add_argument (
47- 'value' , help = 'Value of the parameter' )
68+ '--atomic' , action = 'store_true' ,
69+ help = 'Set all parameters atomically using the SetParametersAtomically service. '
70+ 'Either all parameters are set successfully or none are changed.' )
4871 parser .add_argument (
4972 '--timeout' , metavar = 'N' , type = int , default = 1 ,
5073 help = 'Wait for N seconds until node becomes available (default %(default)s sec)' )
5174
5275 def main (self , * , args ): # noqa: D102
76+ # Validate that parameters were provided as name/value pairs
77+ if len (args .params_and_values ) % 2 != 0 :
78+ return (
79+ 'Parameters must be provided as name/value pairs: '
80+ 'name value [name value ...]. '
81+ f'Got { len (args .params_and_values )} argument(s).'
82+ )
83+
84+ pairs = list (zip (args .params_and_values [::2 ], args .params_and_values [1 ::2 ]))
85+ multi_param = len (pairs ) > 1
86+
5387 node_name = get_absolute_node_name (args .node_name )
5488 with NodeStrategy (args ) as node :
5589 if not wait_for_node (node , node_name , args .include_hidden_nodes , args .timeout ):
5690 return 'Node not found'
5791
5892 with DirectNode (args ) as node :
59- parameter = Parameter ()
60- parameter .name = args .parameter_name
61- parameter .value = get_parameter_value (string_value = args .value )
62-
63- response = call_set_parameters (
64- node = node , node_name = args .node_name , parameters = [parameter ])
65-
66- # output response
67- assert len (response .results ) == 1
68- result = response .results [0 ]
69- if result .successful :
70- msg = 'Set parameter successful'
71- if result .reason :
72- msg += ': ' + result .reason
73- print (msg )
93+ parameters = []
94+ for param_name , param_value_str in pairs :
95+ parameter = Parameter ()
96+ parameter .name = param_name
97+ parameter .value = get_parameter_value (string_value = param_value_str )
98+ parameters .append (parameter )
99+
100+ if args .atomic :
101+ # Set all parameters in a single atomic transaction
102+ response = call_set_parameters_atomically (
103+ node = node , node_name = args .node_name , parameters = parameters )
104+
105+ result = response .result
106+ if result .successful :
107+ msg = 'Set parameters atomically successful'
108+ if result .reason :
109+ msg += ': ' + result .reason
110+ print (msg )
111+ else :
112+ msg = 'Setting parameters atomically failed'
113+ if result .reason :
114+ msg += ': ' + result .reason
115+ print (msg , file = sys .stderr )
74116 else :
75- msg = 'Setting parameter failed'
76- if result .reason :
77- msg += ': ' + result .reason
78- print (msg , file = sys .stderr )
117+ response = call_set_parameters (
118+ node = node , node_name = args .node_name , parameters = parameters )
119+
120+ # output response
121+ assert len (response .results ) == len (parameters )
122+ for (param_name , _ ), result in zip (pairs , response .results ):
123+ if result .successful :
124+ msg = 'Set parameter successful'
125+ if result .reason :
126+ msg += ': ' + result .reason
127+ if multi_param :
128+ print (f'{ param_name } : { msg } ' )
129+ else :
130+ print (msg )
131+ else :
132+ msg = 'Setting parameter failed'
133+ if result .reason :
134+ msg += ': ' + result .reason
135+ if multi_param :
136+ print (f'{ param_name } : { msg } ' , file = sys .stderr )
137+ else :
138+ print (msg , file = sys .stderr )
0 commit comments