ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
node_parameters.cpp
1 // Copyright 2016 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "rclcpp/node_interfaces/node_parameters.hpp"
16 
17 #include <rcl_yaml_param_parser/parser.h>
18 
19 #include <array>
20 #include <cmath>
21 #include <cstdlib>
22 #include <cstring>
23 #include <functional>
24 #include <limits>
25 #include <map>
26 #include <memory>
27 #include <sstream>
28 #include <string>
29 #include <utility>
30 #include <vector>
31 
32 #include "rcl_interfaces/srv/list_parameters.hpp"
33 #include "rclcpp/create_publisher.hpp"
34 #include "rclcpp/parameter_map.hpp"
35 #include "rcutils/logging_macros.h"
36 #include "rmw/qos_profiles.h"
37 
38 #include "../detail/resolve_parameter_overrides.hpp"
39 
41 
42 NodeParameters::NodeParameters(
43  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
44  const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
45  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
46  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services,
47  const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
48  const std::vector<rclcpp::Parameter> & parameter_overrides,
49  bool start_parameter_services,
50  bool start_parameter_event_publisher,
51  const rclcpp::QoS & parameter_event_qos,
52  const rclcpp::PublisherOptionsBase & parameter_event_publisher_options,
53  bool allow_undeclared_parameters,
54  bool automatically_declare_parameters_from_overrides)
55 : allow_undeclared_(allow_undeclared_parameters),
56  events_publisher_(nullptr),
57  node_logging_(node_logging),
58  node_clock_(node_clock)
59 {
60  using MessageT = rcl_interfaces::msg::ParameterEvent;
61  using PublisherT = rclcpp::Publisher<MessageT>;
62  using AllocatorT = std::allocator<void>;
63  // TODO(wjwwood): expose this allocator through the Parameter interface.
65  parameter_event_publisher_options);
66  publisher_options.allocator = std::make_shared<AllocatorT>();
67 
68  if (start_parameter_services) {
69  parameter_service_ = std::make_shared<ParameterService>(node_base, node_services, this);
70  }
71 
72  if (start_parameter_event_publisher) {
73  // TODO(ivanpauno): Qos of the `/parameters_event` topic should be somehow overridable.
74  events_publisher_ = rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
75  node_topics,
76  "/parameter_events",
77  parameter_event_qos,
78  publisher_options);
79  }
80 
81  // Get the node options
82  const rcl_node_t * node = node_base->get_rcl_node_handle();
83  if (nullptr == node) {
84  throw std::runtime_error("Need valid node handle in NodeParameters");
85  }
86  const rcl_node_options_t * options = rcl_node_get_options(node);
87  if (nullptr == options) {
88  throw std::runtime_error("Need valid node options in NodeParameters");
89  }
90 
91  const rcl_arguments_t * global_args = nullptr;
92  if (options->use_global_arguments) {
93  auto context_ptr = node_base->get_context()->get_rcl_context();
94  global_args = &(context_ptr->global_arguments);
95  }
96  combined_name_ = node_base->get_fully_qualified_name();
97 
98  parameter_overrides_ = rclcpp::detail::resolve_parameter_overrides(
99  combined_name_, parameter_overrides, &options->arguments, global_args);
100 
101  // If asked, initialize any parameters that ended up in the initial parameter values,
102  // but did not get declared explcitily by this point.
103  if (automatically_declare_parameters_from_overrides) {
104  rcl_interfaces::msg::ParameterDescriptor descriptor;
105  descriptor.dynamic_typing = true;
106  for (const auto & pair : this->get_parameter_overrides()) {
107  if (!this->has_parameter(pair.first)) {
108  this->declare_parameter(
109  pair.first,
110  pair.second,
111  descriptor,
112  true);
113  }
114  }
115  }
116 }
117 
118 NodeParameters::~NodeParameters()
119 {}
120 
121 RCLCPP_LOCAL
122 bool
123 __lockless_has_parameter(
124  const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
125  const std::string & name)
126 {
127  return parameters.find(name) != parameters.end();
128 }
129 
130 // see https://en.cppreference.com/w/cpp/types/numeric_limits/epsilon
131 RCLCPP_LOCAL
132 bool
133 __are_doubles_equal(double x, double y, double ulp = 100.0)
134 {
135  return std::abs(x - y) <= std::numeric_limits<double>::epsilon() * std::abs(x + y) * ulp;
136 }
137 
138 static
139 std::string
140 format_range_reason(const std::string & name, const char * range_type)
141 {
142  std::ostringstream ss;
143  ss << "Parameter {" << name << "} doesn't comply with " << range_type << " range.";
144  return ss.str();
145 }
146 
147 RCLCPP_LOCAL
148 rcl_interfaces::msg::SetParametersResult
149 __check_parameter_value_in_range(
150  const rcl_interfaces::msg::ParameterDescriptor & descriptor,
151  const rclcpp::ParameterValue & value)
152 {
153  rcl_interfaces::msg::SetParametersResult result;
154  result.successful = true;
155  if (!descriptor.integer_range.empty() && value.get_type() == rclcpp::PARAMETER_INTEGER) {
156  int64_t v = value.get<int64_t>();
157  auto integer_range = descriptor.integer_range.at(0);
158  if (v == integer_range.from_value || v == integer_range.to_value) {
159  return result;
160  }
161  if ((v < integer_range.from_value) || (v > integer_range.to_value)) {
162  result.successful = false;
163  result.reason = format_range_reason(descriptor.name, "integer");
164  return result;
165  }
166  if (integer_range.step == 0) {
167  return result;
168  }
169  if (((v - integer_range.from_value) % integer_range.step) == 0) {
170  return result;
171  }
172  result.successful = false;
173  result.reason = format_range_reason(descriptor.name, "integer");
174  return result;
175  }
176 
177  if (!descriptor.floating_point_range.empty() && value.get_type() == rclcpp::PARAMETER_DOUBLE) {
178  double v = value.get<double>();
179  auto fp_range = descriptor.floating_point_range.at(0);
180  if (__are_doubles_equal(v, fp_range.from_value) || __are_doubles_equal(v, fp_range.to_value)) {
181  return result;
182  }
183  if ((v < fp_range.from_value) || (v > fp_range.to_value)) {
184  result.successful = false;
185  result.reason = format_range_reason(descriptor.name, "floating point");
186  return result;
187  }
188  if (fp_range.step == 0.0) {
189  return result;
190  }
191  double rounded_div = std::round((v - fp_range.from_value) / fp_range.step);
192  if (__are_doubles_equal(v, fp_range.from_value + rounded_div * fp_range.step)) {
193  return result;
194  }
195  result.successful = false;
196  result.reason = format_range_reason(descriptor.name, "floating point");
197  return result;
198  }
199  return result;
200 }
201 
202 static
203 std::string
204 format_type_reason(
205  const std::string & name, const std::string & old_type, const std::string & new_type)
206 {
207  std::ostringstream ss;
208  // WARN: A condition later depends on this message starting with "Wrong parameter type",
209  // check `declare_parameter` if you modify this!
210  ss << "Wrong parameter type, parameter {" << name << "} is of type {" << old_type <<
211  "}, setting it to {" << new_type << "} is not allowed.";
212  return ss.str();
213 }
214 
215 // Return true if parameter values comply with the descriptors in parameter_infos.
216 RCLCPP_LOCAL
217 rcl_interfaces::msg::SetParametersResult
218 __check_parameters(
219  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameter_infos,
220  const std::vector<rclcpp::Parameter> & parameters,
221  bool allow_undeclared)
222 {
223  rcl_interfaces::msg::SetParametersResult result;
224  result.successful = true;
225  for (const rclcpp::Parameter & parameter : parameters) {
226  std::string name = parameter.get_name();
227  rcl_interfaces::msg::ParameterDescriptor descriptor;
228  if (allow_undeclared) {
229  auto it = parameter_infos.find(name);
230  if (it != parameter_infos.cend()) {
231  descriptor = it->second.descriptor;
232  } else {
233  // implicitly declared parameters are dinamically typed!
234  descriptor.dynamic_typing = true;
235  }
236  } else {
237  descriptor = parameter_infos[name].descriptor;
238  }
239  if (descriptor.name.empty()) {
240  descriptor.name = name;
241  }
242  const auto new_type = parameter.get_type();
243  const auto specified_type = static_cast<rclcpp::ParameterType>(descriptor.type);
244  result.successful = descriptor.dynamic_typing || specified_type == new_type;
245  if (!result.successful) {
246  result.reason = format_type_reason(
247  name, rclcpp::to_string(specified_type), rclcpp::to_string(new_type));
248  return result;
249  }
250  result = __check_parameter_value_in_range(
251  descriptor,
252  parameter.get_parameter_value());
253  if (!result.successful) {
254  return result;
255  }
256  }
257  return result;
258 }
259 
260 using OnParametersSetCallbackType =
261  rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType;
262 using CallbacksContainerType =
263  rclcpp::node_interfaces::NodeParameters::CallbacksContainerType;
266 
267 RCLCPP_LOCAL
268 rcl_interfaces::msg::SetParametersResult
269 __call_on_parameters_set_callbacks(
270  const std::vector<rclcpp::Parameter> & parameters,
271  CallbacksContainerType & callback_container,
272  const OnParametersSetCallbackType & callback)
273 {
274  rcl_interfaces::msg::SetParametersResult result;
275  result.successful = true;
276  auto it = callback_container.begin();
277  while (it != callback_container.end()) {
278  auto shared_handle = it->lock();
279  if (nullptr != shared_handle) {
280  result = shared_handle->callback(parameters);
281  if (!result.successful) {
282  return result;
283  }
284  it++;
285  } else {
286  it = callback_container.erase(it);
287  }
288  }
289  if (callback) {
290  result = callback(parameters);
291  }
292  return result;
293 }
294 
295 RCLCPP_LOCAL
296 rcl_interfaces::msg::SetParametersResult
297 __set_parameters_atomically_common(
298  const std::vector<rclcpp::Parameter> & parameters,
299  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameter_infos,
300  CallbacksContainerType & callback_container,
301  const OnParametersSetCallbackType & callback,
302  bool allow_undeclared = false)
303 {
304  // Check if the value being set complies with the descriptor.
305  rcl_interfaces::msg::SetParametersResult result = __check_parameters(
306  parameter_infos, parameters, allow_undeclared);
307  if (!result.successful) {
308  return result;
309  }
310  // Call the user callback to see if the new value(s) are allowed.
311  result =
312  __call_on_parameters_set_callbacks(parameters, callback_container, callback);
313  if (!result.successful) {
314  return result;
315  }
316  // If accepted, actually set the values.
317  if (result.successful) {
318  for (size_t i = 0; i < parameters.size(); ++i) {
319  const std::string & name = parameters[i].get_name();
320  parameter_infos[name].descriptor.name = parameters[i].get_name();
321  parameter_infos[name].descriptor.type = parameters[i].get_type();
322  parameter_infos[name].value = parameters[i].get_parameter_value();
323  }
324  }
325 
326  // Either way, return the result.
327  return result;
328 }
329 
330 RCLCPP_LOCAL
331 rcl_interfaces::msg::SetParametersResult
332 __declare_parameter_common(
333  const std::string & name,
334  const rclcpp::ParameterValue & default_value,
335  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
336  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters_out,
337  const std::map<std::string, rclcpp::ParameterValue> & overrides,
338  CallbacksContainerType & callback_container,
339  const OnParametersSetCallbackType & callback,
340  rcl_interfaces::msg::ParameterEvent * parameter_event_out,
341  bool ignore_override = false)
342 {
344  std::map<std::string, ParameterInfo> parameter_infos {{name, ParameterInfo()}};
345  parameter_infos.at(name).descriptor = parameter_descriptor;
346 
347  // Use the value from the overrides if available, otherwise use the default.
348  const rclcpp::ParameterValue * initial_value = &default_value;
349  auto overrides_it = overrides.find(name);
350  if (!ignore_override && overrides_it != overrides.end()) {
351  initial_value = &overrides_it->second;
352  }
353 
354  // If there is no initial value, then skip initialization
355  if (initial_value->get_type() == rclcpp::PARAMETER_NOT_SET) {
356  // Add declared parameters to storage (without a value)
357  parameter_infos[name].descriptor.name = name;
358  if (parameter_descriptor.dynamic_typing) {
359  parameter_infos[name].descriptor.type = rclcpp::PARAMETER_NOT_SET;
360  } else {
361  parameter_infos[name].descriptor.type = parameter_descriptor.type;
362  }
363  parameters_out[name] = parameter_infos.at(name);
364  rcl_interfaces::msg::SetParametersResult result;
365  result.successful = true;
366  return result;
367  }
368 
369  // Check with the user's callback to see if the initial value can be set.
370  std::vector<rclcpp::Parameter> parameter_wrappers {rclcpp::Parameter(name, *initial_value)};
371  // This function also takes care of default vs initial value.
372  auto result = __set_parameters_atomically_common(
373  parameter_wrappers,
374  parameter_infos,
375  callback_container,
376  callback);
377 
378  if (!result.successful) {
379  return result;
380  }
381 
382  // Add declared parameters to storage.
383  parameters_out[name] = parameter_infos.at(name);
384 
385  // Extend the given parameter event, if valid.
386  if (parameter_event_out) {
387  parameter_event_out->new_parameters.push_back(parameter_wrappers[0].to_parameter_msg());
388  }
389 
390  return result;
391 }
392 
393 static
395 declare_parameter_helper(
396  const std::string & name,
397  rclcpp::ParameterType type,
398  const rclcpp::ParameterValue & default_value,
399  rcl_interfaces::msg::ParameterDescriptor parameter_descriptor,
400  bool ignore_override,
401  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
402  const std::map<std::string, rclcpp::ParameterValue> & overrides,
403  CallbacksContainerType & callback_container,
404  const OnParametersSetCallbackType & callback,
406  const std::string & combined_name,
408 {
409  // TODO(sloretz) parameter name validation
410  if (name.empty()) {
411  throw rclcpp::exceptions::InvalidParametersException("parameter name must not be empty");
412  }
413 
414  // Error if this parameter has already been declared and is different
415  if (__lockless_has_parameter(parameters, name)) {
417  "parameter '" + name + "' has already been declared");
418  }
419 
420  if (!parameter_descriptor.dynamic_typing) {
421  if (rclcpp::PARAMETER_NOT_SET == type) {
422  type = default_value.get_type();
423  }
424  if (rclcpp::PARAMETER_NOT_SET == type) {
426  name,
427  "cannot declare a statically typed parameter with an uninitialized value"
428  };
429  }
430  parameter_descriptor.type = static_cast<uint8_t>(type);
431  }
432 
433  rcl_interfaces::msg::ParameterEvent parameter_event;
434  auto result = __declare_parameter_common(
435  name,
436  default_value,
437  parameter_descriptor,
438  parameters,
439  overrides,
440  callback_container,
441  callback,
442  &parameter_event,
443  ignore_override);
444 
445  // If it failed to be set, then throw an exception.
446  if (!result.successful) {
447  constexpr const char type_error_msg_start[] = "Wrong parameter type";
448  if (
449  0u == std::strncmp(
450  result.reason.c_str(), type_error_msg_start, sizeof(type_error_msg_start) - 1))
451  {
452  // TODO(ivanpauno): Refactor the logic so we don't need the above `strncmp` and we can
453  // detect between both exceptions more elegantly.
454  throw rclcpp::exceptions::InvalidParameterTypeException(name, result.reason);
455  }
457  "parameter '" + name + "' could not be set: " + result.reason);
458  }
459 
460  // Publish if events_publisher_ is not nullptr, which may be if disabled in the constructor.
461  if (nullptr != events_publisher) {
462  parameter_event.node = combined_name;
463  parameter_event.stamp = node_clock.get_clock()->now();
464  events_publisher->publish(parameter_event);
465  }
466 
467  return parameters.at(name).value;
468 }
469 
472  const std::string & name,
473  const rclcpp::ParameterValue & default_value,
474  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
475  bool ignore_override)
476 {
477  std::lock_guard<std::recursive_mutex> lock(mutex_);
478  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
479 
480  return declare_parameter_helper(
481  name,
482  rclcpp::PARAMETER_NOT_SET,
483  default_value,
484  parameter_descriptor,
485  ignore_override,
486  parameters_,
487  parameter_overrides_,
488  on_parameters_set_callback_container_,
489  on_parameters_set_callback_,
490  events_publisher_.get(),
491  combined_name_,
492  *node_clock_);
493 }
494 
497  const std::string & name,
498  rclcpp::ParameterType type,
499  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
500  bool ignore_override)
501 {
502  std::lock_guard<std::recursive_mutex> lock(mutex_);
503  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
504 
505  if (rclcpp::PARAMETER_NOT_SET == type) {
506  throw std::invalid_argument{
507  "declare_parameter(): the provided parameter type cannot be rclcpp::PARAMETER_NOT_SET"};
508  }
509 
510  if (parameter_descriptor.dynamic_typing == true) {
511  throw std::invalid_argument{
512  "declare_parameter(): cannot declare parameter of specific type and pass descriptor"
513  "with `dynamic_typing=true`"};
514  }
515 
516  return declare_parameter_helper(
517  name,
518  type,
520  parameter_descriptor,
521  ignore_override,
522  parameters_,
523  parameter_overrides_,
524  on_parameters_set_callback_container_,
525  on_parameters_set_callback_,
526  events_publisher_.get(),
527  combined_name_,
528  *node_clock_);
529 }
530 
531 void
532 NodeParameters::undeclare_parameter(const std::string & name)
533 {
534  std::lock_guard<std::recursive_mutex> lock(mutex_);
535 
536  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
537 
538  auto parameter_info = parameters_.find(name);
539  if (parameter_info == parameters_.end()) {
541  "cannot undeclare parameter '" + name + "' which has not yet been declared");
542  }
543 
544  if (parameter_info->second.descriptor.read_only) {
546  "cannot undeclare parameter '" + name + "' because it is read-only");
547  }
548  if (!parameter_info->second.descriptor.dynamic_typing) {
550  name, "cannot undeclare an statically typed parameter"};
551  }
552 
553  parameters_.erase(parameter_info);
554 }
555 
556 bool
557 NodeParameters::has_parameter(const std::string & name) const
558 {
559  std::lock_guard<std::recursive_mutex> lock(mutex_);
560 
561  return __lockless_has_parameter(parameters_, name);
562 }
563 
564 std::vector<rcl_interfaces::msg::SetParametersResult>
565 NodeParameters::set_parameters(const std::vector<rclcpp::Parameter> & parameters)
566 {
567  std::vector<rcl_interfaces::msg::SetParametersResult> results;
568  results.reserve(parameters.size());
569 
570  for (const auto & p : parameters) {
571  auto result = set_parameters_atomically({{p}});
572  results.push_back(result);
573  }
574 
575  return results;
576 }
577 
578 template<typename ParameterVectorType>
579 auto
580 __find_parameter_by_name(
581  ParameterVectorType & parameters,
582  const std::string & name)
583 {
584  return std::find_if(
585  parameters.begin(),
586  parameters.end(),
587  [&](auto parameter) {return parameter.get_name() == name;});
588 }
589 
590 rcl_interfaces::msg::SetParametersResult
591 NodeParameters::set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters)
592 {
593  std::lock_guard<std::recursive_mutex> lock(mutex_);
594 
595  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
596 
597  rcl_interfaces::msg::SetParametersResult result;
598 
599  // Check if any of the parameters are read-only, or if any parameters are not
600  // declared.
601  // If not declared, keep track of them in order to declare them later, when
602  // undeclared parameters are allowed, and if they're not allowed, fail.
603  std::vector<const rclcpp::Parameter *> parameters_to_be_declared;
604  for (const auto & parameter : parameters) {
605  const std::string & name = parameter.get_name();
606 
607  // Check to make sure the parameter name is valid.
608  if (name.empty()) {
609  throw rclcpp::exceptions::InvalidParametersException("parameter name must not be empty");
610  }
611 
612  // Check to see if it is declared.
613  auto parameter_info = parameters_.find(name);
614  if (parameter_info == parameters_.end()) {
615  // If not check to see if undeclared paramaters are allowed, ...
616  if (allow_undeclared_) {
617  // If so, mark the parameter to be declared for the user implicitly.
618  parameters_to_be_declared.push_back(&parameter);
619  // continue as it cannot be read-only, and because the declare will
620  // implicitly set the parameter and parameter_infos is for setting only.
621  continue;
622  } else {
623  // If not, then throw the exception as documented.
625  "parameter '" + name + "' cannot be set because it was not declared");
626  }
627  }
628 
629  // Check to see if it is read-only.
630  if (parameter_info->second.descriptor.read_only) {
631  result.successful = false;
632  result.reason = "parameter '" + name + "' cannot be set because it is read-only";
633  return result;
634  }
635  }
636 
637  // Declare parameters into a temporary "staging area", incase one of the declares fail.
638  // We will use the staged changes as input to the "set atomically" action.
639  // We explicitly avoid calling the user callback here, so that it may be called once, with
640  // all the other parameters to be set (already declared parameters).
641  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> staged_parameter_changes;
642  rcl_interfaces::msg::ParameterEvent parameter_event_msg;
643  parameter_event_msg.node = combined_name_;
644  CallbacksContainerType empty_callback_container;
645 
646  // Implicit declare uses dynamic type descriptor.
647  rcl_interfaces::msg::ParameterDescriptor descriptor;
648  descriptor.dynamic_typing = true;
649  for (auto parameter_to_be_declared : parameters_to_be_declared) {
650  // This should not throw, because we validated the name and checked that
651  // the parameter was not already declared.
652  result = __declare_parameter_common(
653  parameter_to_be_declared->get_name(),
654  parameter_to_be_declared->get_parameter_value(),
655  descriptor,
656  staged_parameter_changes,
657  parameter_overrides_,
658  // Only call callbacks once below
659  empty_callback_container, // callback_container is explicitly empty
660  nullptr, // callback is explicitly null.
661  &parameter_event_msg,
662  true);
663  if (!result.successful) {
664  // Declare failed, return knowing that nothing was changed because the
665  // staged changes were not applied.
666  return result;
667  }
668  }
669 
670  // If there were implicitly declared parameters, then we may need to copy the input parameters
671  // and then assign the value that was selected after the declare (could be affected by the
672  // initial parameter values).
673  const std::vector<rclcpp::Parameter> * parameters_to_be_set = &parameters;
674  std::vector<rclcpp::Parameter> parameters_copy;
675  if (0 != staged_parameter_changes.size()) { // If there were any implicitly declared parameters.
676  bool any_initial_values_used = false;
677  for (const auto & staged_parameter_change : staged_parameter_changes) {
678  auto it = __find_parameter_by_name(parameters, staged_parameter_change.first);
679  if (it->get_parameter_value() != staged_parameter_change.second.value) {
680  // In this case, the value of the staged parameter differs from the
681  // input from the user, and therefore we need to update things before setting.
682  any_initial_values_used = true;
683  // No need to search further since at least one initial value needs to be used.
684  break;
685  }
686  }
687  if (any_initial_values_used) {
688  parameters_copy = parameters;
689  for (const auto & staged_parameter_change : staged_parameter_changes) {
690  auto it = __find_parameter_by_name(parameters_copy, staged_parameter_change.first);
691  *it = Parameter(staged_parameter_change.first, staged_parameter_change.second.value);
692  }
693  parameters_to_be_set = &parameters_copy;
694  }
695  }
696 
697  // Collect parameters who will have had their type changed to
698  // rclcpp::PARAMETER_NOT_SET so they can later be implicitly undeclared.
699  std::vector<const rclcpp::Parameter *> parameters_to_be_undeclared;
700  for (const auto & parameter : *parameters_to_be_set) {
701  if (rclcpp::PARAMETER_NOT_SET == parameter.get_type()) {
702  auto it = parameters_.find(parameter.get_name());
703  if (it != parameters_.end() && rclcpp::PARAMETER_NOT_SET != it->second.value.get_type()) {
704  if (!it->second.descriptor.dynamic_typing) {
705  result.reason = "cannot undeclare an statically typed parameter";
706  result.successful = false;
707  return result;
708  }
709  parameters_to_be_undeclared.push_back(&parameter);
710  }
711  }
712  }
713 
714  // Set all of the parameters including the ones declared implicitly above.
715  result = __set_parameters_atomically_common(
716  // either the original parameters given by the user, or ones updated with initial values
717  *parameters_to_be_set,
718  // they are actually set on the official parameter storage
719  parameters_,
720  // this will get called once, with all the parameters to be set
721  on_parameters_set_callback_container_,
722  // These callbacks are called once. When a callback returns an unsuccessful result,
723  // the remaining aren't called.
724  on_parameters_set_callback_,
725  allow_undeclared_); // allow undeclared
726 
727  // If not successful, then stop here.
728  if (!result.successful) {
729  return result;
730  }
731 
732  // If successful, then update the parameter infos from the implicitly declared parameter's.
733  for (const auto & kv_pair : staged_parameter_changes) {
734  // assumption: the parameter is already present in parameters_ due to the above "set"
735  assert(__lockless_has_parameter(parameters_, kv_pair.first));
736  // assumption: the value in parameters_ is the same as the value resulting from the declare
737  assert(parameters_[kv_pair.first].value == kv_pair.second.value);
738  // This assignment should not change the name, type, or value, but may
739  // change other things from the ParameterInfo.
740  parameters_[kv_pair.first] = kv_pair.second;
741  }
742 
743  // Undeclare parameters that need to be.
744  for (auto parameter_to_undeclare : parameters_to_be_undeclared) {
745  auto it = parameters_.find(parameter_to_undeclare->get_name());
746  // assumption: the parameter to be undeclared should be in the parameter infos map
747  assert(it != parameters_.end());
748  if (it != parameters_.end()) {
749  // Update the parameter event message and remove it.
750  parameter_event_msg.deleted_parameters.push_back(
751  rclcpp::Parameter(it->first, it->second.value).to_parameter_msg());
752  parameters_.erase(it);
753  }
754  }
755 
756  // Update the parameter event message for any parameters which were only set,
757  // and not either declared or undeclared.
758  for (const auto & parameter : *parameters_to_be_set) {
759  if (staged_parameter_changes.find(parameter.get_name()) != staged_parameter_changes.end()) {
760  // This parameter was declared.
761  continue;
762  }
763  auto it = std::find_if(
764  parameters_to_be_undeclared.begin(),
765  parameters_to_be_undeclared.end(),
766  [&parameter](const auto & p) {return p->get_name() == parameter.get_name();});
767  if (it != parameters_to_be_undeclared.end()) {
768  // This parameter was undeclared (deleted).
769  continue;
770  }
771  // This parameter was neither declared nor undeclared.
772  parameter_event_msg.changed_parameters.push_back(parameter.to_parameter_msg());
773  }
774 
775  // Publish if events_publisher_ is not nullptr, which may be if disabled in the constructor.
776  if (nullptr != events_publisher_) {
777  parameter_event_msg.stamp = node_clock_->get_clock()->now();
778  events_publisher_->publish(parameter_event_msg);
779  }
780 
781  return result;
782 }
783 
784 std::vector<rclcpp::Parameter>
785 NodeParameters::get_parameters(const std::vector<std::string> & names) const
786 {
787  std::lock_guard<std::recursive_mutex> lock(mutex_);
788  std::vector<rclcpp::Parameter> results;
789  results.reserve(names.size());
790 
791  for (auto & name : names) {
792  auto found_parameter = parameters_.find(name);
793  if (found_parameter != parameters_.cend()) {
794  // found
795  results.emplace_back(name, found_parameter->second.value);
796  } else if (this->allow_undeclared_) {
797  // not found, but undeclared allowed
798  results.emplace_back(name, rclcpp::ParameterValue());
799  } else {
800  // not found, and undeclared are not allowed
802  }
803  }
804  return results;
805 }
806 
808 NodeParameters::get_parameter(const std::string & name) const
809 {
810  std::lock_guard<std::recursive_mutex> lock(mutex_);
811 
812  auto param_iter = parameters_.find(name);
813  if (
814  parameters_.end() != param_iter &&
815  (param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET ||
816  param_iter->second.descriptor.dynamic_typing))
817  {
818  return rclcpp::Parameter{name, param_iter->second.value};
819  } else if (this->allow_undeclared_) {
820  return rclcpp::Parameter{};
821  } else if (parameters_.end() == param_iter) {
823  } else {
825  }
826 }
827 
828 bool
830  const std::string & name,
831  rclcpp::Parameter & parameter) const
832 {
833  std::lock_guard<std::recursive_mutex> lock(mutex_);
834 
835  auto param_iter = parameters_.find(name);
836  if (
837  parameters_.end() != param_iter &&
838  param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
839  {
840  parameter = {name, param_iter->second.value};
841  return true;
842  } else {
843  return false;
844  }
845 }
846 
847 bool
849  const std::string & prefix,
850  std::map<std::string, rclcpp::Parameter> & parameters) const
851 {
852  std::lock_guard<std::recursive_mutex> lock(mutex_);
853 
854  std::string prefix_with_dot = prefix.empty() ? prefix : prefix + ".";
855  bool ret = false;
856 
857  for (const auto & param : parameters_) {
858  if (param.first.find(prefix_with_dot) == 0 && param.first.length() > prefix_with_dot.length()) {
859  // Found one!
860  parameters[param.first.substr(prefix_with_dot.length())] = rclcpp::Parameter(param.second);
861  ret = true;
862  }
863  }
864 
865  return ret;
866 }
867 
868 std::vector<rcl_interfaces::msg::ParameterDescriptor>
869 NodeParameters::describe_parameters(const std::vector<std::string> & names) const
870 {
871  std::lock_guard<std::recursive_mutex> lock(mutex_);
872  std::vector<rcl_interfaces::msg::ParameterDescriptor> results;
873  results.reserve(names.size());
874 
875  for (const auto & name : names) {
876  auto it = parameters_.find(name);
877  if (it != parameters_.cend()) {
878  results.push_back(it->second.descriptor);
879  } else if (allow_undeclared_) {
880  // parameter not found, but undeclared allowed, so return empty
881  rcl_interfaces::msg::ParameterDescriptor default_description;
882  default_description.name = name;
883  results.push_back(default_description);
884  } else {
886  }
887  }
888 
889  if (results.size() != names.size()) {
890  throw std::runtime_error("results and names unexpectedly different sizes");
891  }
892 
893  return results;
894 }
895 
896 std::vector<uint8_t>
897 NodeParameters::get_parameter_types(const std::vector<std::string> & names) const
898 {
899  std::lock_guard<std::recursive_mutex> lock(mutex_);
900  std::vector<uint8_t> results;
901  results.reserve(names.size());
902 
903  for (const auto & name : names) {
904  auto it = parameters_.find(name);
905  if (it != parameters_.cend()) {
906  results.push_back(it->second.value.get_type());
907  } else if (allow_undeclared_) {
908  // parameter not found, but undeclared allowed, so return not set
909  results.push_back(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
910  } else {
912  }
913  }
914 
915  if (results.size() != names.size()) {
916  throw std::runtime_error("results and names unexpectedly different sizes");
917  }
918 
919  return results;
920 }
921 
922 rcl_interfaces::msg::ListParametersResult
923 NodeParameters::list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const
924 {
925  std::lock_guard<std::recursive_mutex> lock(mutex_);
926  rcl_interfaces::msg::ListParametersResult result;
927 
928  // TODO(mikaelarguedas) define parameter separator different from "/" to avoid ambiguity
929  // using "." for now
930  const char * separator = ".";
931  for (auto & kv : parameters_) {
932  bool get_all = (prefixes.size() == 0) &&
933  ((depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) ||
934  (static_cast<uint64_t>(std::count(kv.first.begin(), kv.first.end(), *separator)) < depth));
935  bool prefix_matches = std::any_of(
936  prefixes.cbegin(), prefixes.cend(),
937  [&kv, &depth, &separator](const std::string & prefix) {
938  if (kv.first == prefix) {
939  return true;
940  } else if (kv.first.find(prefix + separator) == 0) {
941  size_t length = prefix.length();
942  std::string substr = kv.first.substr(length);
943  // Cast as unsigned integer to avoid warning
944  return (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) ||
945  (static_cast<uint64_t>(std::count(substr.begin(), substr.end(), *separator)) < depth);
946  }
947  return false;
948  });
949  if (get_all || prefix_matches) {
950  result.names.push_back(kv.first);
951  size_t last_separator = kv.first.find_last_of(separator);
952  if (std::string::npos != last_separator) {
953  std::string prefix = kv.first.substr(0, last_separator);
954  if (
955  std::find(result.prefixes.cbegin(), result.prefixes.cend(), prefix) ==
956  result.prefixes.cend())
957  {
958  result.prefixes.push_back(prefix);
959  }
960  }
961  }
962  }
963  return result;
964 }
965 
966 void
968  const OnSetParametersCallbackHandle * const handle)
969 {
970  std::lock_guard<std::recursive_mutex> lock(mutex_);
971  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
972 
973  auto it = std::find_if(
974  on_parameters_set_callback_container_.begin(),
975  on_parameters_set_callback_container_.end(),
976  [handle](const auto & weak_handle) {
977  return handle == weak_handle.lock().get();
978  });
979  if (it != on_parameters_set_callback_container_.end()) {
980  on_parameters_set_callback_container_.erase(it);
981  } else {
982  throw std::runtime_error("Callback doesn't exist");
983  }
984 }
985 
986 OnSetParametersCallbackHandle::SharedPtr
987 NodeParameters::add_on_set_parameters_callback(OnParametersSetCallbackType callback)
988 {
989  std::lock_guard<std::recursive_mutex> lock(mutex_);
990  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
991 
992  auto handle = std::make_shared<OnSetParametersCallbackHandle>();
993  handle->callback = callback;
994  // the last callback registered is executed first.
995  on_parameters_set_callback_container_.emplace_front(handle);
996  return handle;
997 }
998 
999 const std::map<std::string, rclcpp::ParameterValue> &
1001 {
1002  return parameter_overrides_;
1003 }
Store the type and value of a parameter.
RCLCPP_PUBLIC ParameterType get_type() const
Return an enum indicating the type of the set value.
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:53
RCLCPP_PUBLIC rcl_interfaces::msg::Parameter to_parameter_msg() const
Convert the class in a parameter message.
Definition: parameter.cpp:151
A publisher publishes messages of any type to a topic.
Definition: publisher.hpp:78
std::enable_if_t< rosidl_generator_traits::is_message< T >::value &&std::is_same< T, ROSMessageType >::value > publish(std::unique_ptr< T, ROSMessageTypeDeleter > msg)
Publish a message on the topic.
Definition: publisher.hpp:254
Encapsulation of Quality of Service settings.
Definition: qos.hpp:111
Thrown if requested parameter type is invalid.
Definition: exceptions.hpp:246
Thrown if passed parameter value is invalid.
Definition: exceptions.hpp:235
Thrown if passed parameters are inconsistent or invalid.
Definition: exceptions.hpp:227
Thrown if parameter is already declared.
Definition: exceptions.hpp:278
Thrown if parameter is immutable and therefore cannot be undeclared.
Definition: exceptions.hpp:292
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
Definition: exceptions.hpp:285
Thrown when an uninitialized parameter is accessed.
Definition: exceptions.hpp:306
Pure virtual interface class for the NodeClock part of the Node API.
virtual RCLCPP_PUBLIC rclcpp::Clock::SharedPtr get_clock()=0
Get a ROS clock which will be kept up to date by the node.
Implementation of the NodeParameters part of the Node API.
RCLCPP_PUBLIC const std::map< std::string, rclcpp::ParameterValue > & get_parameter_overrides() const override
Return the initial parameter values used by the NodeParameters to override default values.
RCLCPP_PUBLIC void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler) override
Remove a callback registered with add_on_set_parameters_callback.
RCLCPP_PUBLIC std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const override
Get descriptions of parameters given their names.
RCLCPP_PUBLIC void undeclare_parameter(const std::string &name) override
Undeclare a parameter.
RCLCPP_PUBLIC const rclcpp::ParameterValue & declare_parameter(const std::string &name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor=rcl_interfaces::msg::ParameterDescriptor{}, bool ignore_override=false) override
Declare and initialize a parameter.
RCLCPP_PUBLIC bool get_parameters_by_prefix(const std::string &prefix, std::map< std::string, rclcpp::Parameter > &parameters) const override
Get all parameters that have the specified prefix into the parameters map.
RCLCPP_PUBLIC std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters) override
Set one or more parameters, one at a time.
RCLCPP_PUBLIC RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback) override
Add a callback for when parameters are being set.
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters) override
Set one or more parameters, all at once.
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const override
Get the description of one parameter given a name.
RCLCPP_PUBLIC bool has_parameter(const std::string &name) const override
Return true if the parameter has been declared, otherwise false.
RCLCPP_PUBLIC std::string to_string(const FutureReturnCode &future_return_code)
String conversion function for FutureReturnCode.
RCL_PUBLIC RCL_WARN_UNUSED const rcl_node_options_t * rcl_node_get_options(const rcl_node_t *node)
Return the rcl node options.
Definition: node.c:462
Hold output of parsing command line arguments.
Definition: arguments.h:36
Structure which encapsulates the options for creating a rcl_node_t.
Definition: node_options.h:35
bool use_global_arguments
If false then only use arguments in this struct, otherwise use global arguments also.
Definition: node_options.h:47
rcl_arguments_t arguments
Command line arguments that apply only to this node.
Definition: node_options.h:50
Structure which encapsulates a ROS Node.
Definition: node.h:42
Non-templated part of PublisherOptionsWithAllocator<Allocator>.
Structure containing optional configuration for Publishers.
rcl_interfaces::msg::ParameterDescriptor descriptor
A description of the parameter.