ROS 2 rclcpp + rcl - jazzy  jazzy
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 RCLCPP_LOCAL
43 void
44 local_perform_automatically_declare_parameters_from_overrides(
45  const std::map<std::string, rclcpp::ParameterValue> & parameter_overrides,
46  std::function<bool(const std::string &)> has_parameter,
47  std::function<void(
48  const std::string &,
49  const rclcpp::ParameterValue &,
50  const rcl_interfaces::msg::ParameterDescriptor &,
51  bool)>
52  declare_parameter)
53 {
54  rcl_interfaces::msg::ParameterDescriptor descriptor;
55  descriptor.dynamic_typing = true;
56  for (const auto & pair : parameter_overrides) {
57  if (!has_parameter(pair.first)) {
58  declare_parameter(
59  pair.first,
60  pair.second,
61  descriptor,
62  true);
63  }
64  }
65 }
66 
67 NodeParameters::NodeParameters(
68  const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
69  const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
70  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
71  const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services,
72  const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
73  const std::vector<rclcpp::Parameter> & parameter_overrides,
74  bool start_parameter_services,
75  bool start_parameter_event_publisher,
76  const rclcpp::QoS & parameter_event_qos,
77  const rclcpp::PublisherOptionsBase & parameter_event_publisher_options,
78  bool allow_undeclared_parameters,
79  bool automatically_declare_parameters_from_overrides)
80 : allow_undeclared_(allow_undeclared_parameters),
81  events_publisher_(nullptr),
82  node_logging_(node_logging),
83  node_clock_(node_clock)
84 {
85  using MessageT = rcl_interfaces::msg::ParameterEvent;
86  using PublisherT = rclcpp::Publisher<MessageT>;
87  using AllocatorT = std::allocator<void>;
88  // TODO(wjwwood): expose this allocator through the Parameter interface.
90  parameter_event_publisher_options);
91  publisher_options.allocator = std::make_shared<AllocatorT>();
92 
93  if (start_parameter_services) {
94  parameter_service_ = std::make_shared<ParameterService>(node_base, node_services, this);
95  }
96 
97  if (start_parameter_event_publisher) {
98  // TODO(ivanpauno): Qos of the `/parameters_event` topic should be somehow overridable.
99  events_publisher_ = rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
100  node_topics,
101  "/parameter_events",
102  parameter_event_qos,
103  publisher_options);
104  }
105 
106  // Get the node options
107  const rcl_node_t * node = node_base->get_rcl_node_handle();
108  if (nullptr == node) {
109  throw std::runtime_error("Need valid node handle in NodeParameters");
110  }
111  const rcl_node_options_t * options = rcl_node_get_options(node);
112  if (nullptr == options) {
113  throw std::runtime_error("Need valid node options in NodeParameters");
114  }
115 
116  const rcl_arguments_t * global_args = nullptr;
117  if (options->use_global_arguments) {
118  auto context_ptr = node_base->get_context()->get_rcl_context();
119  global_args = &(context_ptr->global_arguments);
120  }
121  combined_name_ = node_base->get_fully_qualified_name();
122 
123  parameter_overrides_ = rclcpp::detail::resolve_parameter_overrides(
124  combined_name_, parameter_overrides, &options->arguments, global_args);
125 
126  // If asked, initialize any parameters that ended up in the initial parameter values,
127  // but did not get declared explcitily by this point.
128  if (automatically_declare_parameters_from_overrides) {
129  using namespace std::placeholders;
130  local_perform_automatically_declare_parameters_from_overrides(
131  this->get_parameter_overrides(),
132  std::bind(&NodeParameters::has_parameter, this, _1),
133  [this](
134  const std::string & name,
135  const rclcpp::ParameterValue & default_value,
136  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
137  bool ignore_override)
138  {
140  name, default_value, parameter_descriptor, ignore_override);
141  }
142  );
143  }
144 }
145 
146 void
147 NodeParameters::perform_automatically_declare_parameters_from_overrides()
148 {
149  local_perform_automatically_declare_parameters_from_overrides(
150  this->get_parameter_overrides(),
151  [this](const std::string & name) {
152  return this->has_parameter(name);
153  },
154  [this](
155  const std::string & name,
156  const rclcpp::ParameterValue & default_value,
157  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
158  bool ignore_override)
159  {
160  this->declare_parameter(
161  name, default_value, parameter_descriptor, ignore_override);
162  }
163  );
164 }
165 
166 NodeParameters::~NodeParameters()
167 {}
168 
169 RCLCPP_LOCAL
170 bool
171 __lockless_has_parameter(
172  const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
173  const std::string & name)
174 {
175  return parameters.find(name) != parameters.end();
176 }
177 
178 // see https://en.cppreference.com/w/cpp/types/numeric_limits/epsilon
179 RCLCPP_LOCAL
180 bool
181 __are_doubles_equal(double x, double y, double ulp = 100.0)
182 {
183  return std::abs(x - y) <= std::numeric_limits<double>::epsilon() * std::abs(x + y) * ulp;
184 }
185 
186 static
187 std::string
188 format_range_reason(const std::string & name, const char * range_type)
189 {
190  std::ostringstream ss;
191  ss << "Parameter {" << name << "} doesn't comply with " << range_type << " range.";
192  return ss.str();
193 }
194 
195 RCLCPP_LOCAL
196 rcl_interfaces::msg::SetParametersResult
197 __check_parameter_value_in_range(
198  const rcl_interfaces::msg::ParameterDescriptor & descriptor,
199  const rclcpp::ParameterValue & value)
200 {
201  rcl_interfaces::msg::SetParametersResult result;
202  result.successful = true;
203  if (!descriptor.integer_range.empty() && value.get_type() == rclcpp::PARAMETER_INTEGER) {
204  int64_t v = value.get<int64_t>();
205  auto integer_range = descriptor.integer_range.at(0);
206  if (v == integer_range.from_value || v == integer_range.to_value) {
207  return result;
208  }
209  if ((v < integer_range.from_value) || (v > integer_range.to_value)) {
210  result.successful = false;
211  result.reason = format_range_reason(descriptor.name, "integer");
212  return result;
213  }
214  if (integer_range.step == 0) {
215  return result;
216  }
217  if (((v - integer_range.from_value) % integer_range.step) == 0) {
218  return result;
219  }
220  result.successful = false;
221  result.reason = format_range_reason(descriptor.name, "integer");
222  return result;
223  }
224 
225  if (!descriptor.floating_point_range.empty() && value.get_type() == rclcpp::PARAMETER_DOUBLE) {
226  double v = value.get<double>();
227  auto fp_range = descriptor.floating_point_range.at(0);
228  if (__are_doubles_equal(v, fp_range.from_value) || __are_doubles_equal(v, fp_range.to_value)) {
229  return result;
230  }
231  if ((v < fp_range.from_value) || (v > fp_range.to_value)) {
232  result.successful = false;
233  result.reason = format_range_reason(descriptor.name, "floating point");
234  return result;
235  }
236  if (fp_range.step == 0.0) {
237  return result;
238  }
239  double rounded_div = std::round((v - fp_range.from_value) / fp_range.step);
240  if (__are_doubles_equal(v, fp_range.from_value + rounded_div * fp_range.step)) {
241  return result;
242  }
243  result.successful = false;
244  result.reason = format_range_reason(descriptor.name, "floating point");
245  return result;
246  }
247  return result;
248 }
249 
250 static
251 std::string
252 format_type_reason(
253  const std::string & name, const std::string & old_type, const std::string & new_type)
254 {
255  std::ostringstream ss;
256  // WARN: A condition later depends on this message starting with "Wrong parameter type",
257  // check `declare_parameter` if you modify this!
258  ss << "Wrong parameter type, parameter {" << name << "} is of type {" << old_type <<
259  "}, setting it to {" << new_type << "} is not allowed.";
260  return ss.str();
261 }
262 
263 // Return true if parameter values comply with the descriptors in parameter_infos.
264 RCLCPP_LOCAL
265 rcl_interfaces::msg::SetParametersResult
266 __check_parameters(
267  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameter_infos,
268  const std::vector<rclcpp::Parameter> & parameters,
269  bool allow_undeclared)
270 {
271  rcl_interfaces::msg::SetParametersResult result;
272  result.successful = true;
273  for (const rclcpp::Parameter & parameter : parameters) {
274  std::string name = parameter.get_name();
275  rcl_interfaces::msg::ParameterDescriptor descriptor;
276  if (allow_undeclared) {
277  auto it = parameter_infos.find(name);
278  if (it != parameter_infos.cend()) {
279  descriptor = it->second.descriptor;
280  } else {
281  // implicitly declared parameters are dinamically typed!
282  descriptor.dynamic_typing = true;
283  }
284  } else {
285  descriptor = parameter_infos[name].descriptor;
286  }
287  if (descriptor.name.empty()) {
288  descriptor.name = name;
289  }
290  const auto new_type = parameter.get_type();
291  const auto specified_type = static_cast<rclcpp::ParameterType>(descriptor.type);
292  result.successful = descriptor.dynamic_typing || specified_type == new_type;
293  if (!result.successful) {
294  result.reason = format_type_reason(
295  name, rclcpp::to_string(specified_type), rclcpp::to_string(new_type));
296  return result;
297  }
298  result = __check_parameter_value_in_range(
299  descriptor,
300  parameter.get_parameter_value());
301  if (!result.successful) {
302  return result;
303  }
304  }
305  return result;
306 }
307 
308 using PreSetParametersCallbackType =
309  rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType;
312 using PreSetCallbacksHandleContainer =
313  rclcpp::node_interfaces::NodeParameters::PreSetCallbacksHandleContainer;
314 
315 using OnSetParametersCallbackType =
316  rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType;
319 using OnSetCallbacksHandleContainer =
320  rclcpp::node_interfaces::NodeParameters::OnSetCallbacksHandleContainer;
321 
322 using PostSetParametersCallbackType =
323  rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType;
326 using PostSetCallbacksHandleContainer =
327  rclcpp::node_interfaces::NodeParameters::PostSetCallbacksHandleContainer;
328 
329 RCLCPP_LOCAL
330 void
331 __call_pre_set_parameters_callbacks(
332  std::vector<rclcpp::Parameter> & parameters,
333  PreSetCallbacksHandleContainer & callback_container)
334 {
335  if (callback_container.empty()) {
336  return;
337  }
338 
339  auto it = callback_container.begin();
340  while (it != callback_container.end()) {
341  auto shared_handle = it->lock();
342  if (nullptr != shared_handle) {
343  shared_handle->callback(parameters);
344  it++;
345  } else {
346  it = callback_container.erase(it);
347  }
348  }
349 }
350 
351 RCLCPP_LOCAL
352 rcl_interfaces::msg::SetParametersResult
353 __call_on_set_parameters_callbacks(
354  const std::vector<rclcpp::Parameter> & parameters,
355  OnSetCallbacksHandleContainer & callback_container)
356 {
357  rcl_interfaces::msg::SetParametersResult result;
358  result.successful = true;
359  auto it = callback_container.begin();
360  while (it != callback_container.end()) {
361  auto shared_handle = it->lock();
362  if (nullptr != shared_handle) {
363  result = shared_handle->callback(parameters);
364  if (!result.successful) {
365  return result;
366  }
367  it++;
368  } else {
369  it = callback_container.erase(it);
370  }
371  }
372  return result;
373 }
374 
375 RCLCPP_LOCAL
376 void __call_post_set_parameters_callbacks(
377  const std::vector<rclcpp::Parameter> & parameters,
378  PostSetCallbacksHandleContainer & callback_container)
379 {
380  if (callback_container.empty()) {
381  return;
382  }
383 
384  auto it = callback_container.begin();
385  while (it != callback_container.end()) {
386  auto shared_handle = it->lock();
387  if (nullptr != shared_handle) {
388  shared_handle->callback(parameters);
389  it++;
390  } else {
391  it = callback_container.erase(it);
392  }
393  }
394 }
395 
396 RCLCPP_LOCAL
397 rcl_interfaces::msg::SetParametersResult
398 __set_parameters_atomically_common(
399  const std::vector<rclcpp::Parameter> & parameters,
400  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameter_infos,
401  OnSetCallbacksHandleContainer & on_set_callback_container,
402  PostSetCallbacksHandleContainer & post_set_callback_container,
403  bool allow_undeclared = false)
404 {
405  // Check if the value being set complies with the descriptor.
406  rcl_interfaces::msg::SetParametersResult result = __check_parameters(
407  parameter_infos, parameters, allow_undeclared);
408  if (!result.successful) {
409  return result;
410  }
411  // Call the user callbacks to see if the new value(s) are allowed.
412  result =
413  __call_on_set_parameters_callbacks(parameters, on_set_callback_container);
414  if (!result.successful) {
415  return result;
416  }
417  // If accepted, actually set the values.
418  if (result.successful) {
419  for (size_t i = 0; i < parameters.size(); ++i) {
420  const std::string & name = parameters[i].get_name();
421  parameter_infos[name].descriptor.name = parameters[i].get_name();
422  parameter_infos[name].descriptor.type = parameters[i].get_type();
423  parameter_infos[name].value = parameters[i].get_parameter_value();
424  }
425  // Call the user post set parameter callback
426  __call_post_set_parameters_callbacks(parameters, post_set_callback_container);
427  }
428 
429  // Either way, return the result.
430  return result;
431 }
432 
433 RCLCPP_LOCAL
434 rcl_interfaces::msg::SetParametersResult
435 __declare_parameter_common(
436  const std::string & name,
437  const rclcpp::ParameterValue & default_value,
438  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
439  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters_out,
440  const std::map<std::string, rclcpp::ParameterValue> & overrides,
441  OnSetCallbacksHandleContainer & on_set_callback_container,
442  PostSetCallbacksHandleContainer & post_set_callback_container,
443  rcl_interfaces::msg::ParameterEvent * parameter_event_out,
444  bool ignore_override = false)
445 {
447  std::map<std::string, ParameterInfo> parameter_infos {{name, ParameterInfo()}};
448  parameter_infos.at(name).descriptor = parameter_descriptor;
449 
450  // Use the value from the overrides if available, otherwise use the default.
451  const rclcpp::ParameterValue * initial_value = &default_value;
452  auto overrides_it = overrides.find(name);
453  if (!ignore_override && overrides_it != overrides.end()) {
454  initial_value = &overrides_it->second;
455  }
456 
457  // If there is no initial value, then skip initialization
458  if (initial_value->get_type() == rclcpp::PARAMETER_NOT_SET) {
459  // Add declared parameters to storage (without a value)
460  parameter_infos[name].descriptor.name = name;
461  if (parameter_descriptor.dynamic_typing) {
462  parameter_infos[name].descriptor.type = rclcpp::PARAMETER_NOT_SET;
463  } else {
464  parameter_infos[name].descriptor.type = parameter_descriptor.type;
465  }
466  parameters_out[name] = parameter_infos.at(name);
467  rcl_interfaces::msg::SetParametersResult result;
468  result.successful = true;
469  return result;
470  }
471 
472  // Check with the user's callbacks to see if the initial value can be set.
473  std::vector<rclcpp::Parameter> parameter_wrappers {rclcpp::Parameter(name, *initial_value)};
474  // This function also takes care of default vs initial value.
475  auto result = __set_parameters_atomically_common(
476  parameter_wrappers,
477  parameter_infos,
478  on_set_callback_container,
479  post_set_callback_container
480  );
481 
482  if (!result.successful) {
483  return result;
484  }
485 
486  // Add declared parameters to storage.
487  parameters_out[name] = parameter_infos.at(name);
488 
489  // Extend the given parameter event, if valid.
490  if (parameter_event_out) {
491  parameter_event_out->new_parameters.push_back(parameter_wrappers[0].to_parameter_msg());
492  }
493 
494  return result;
495 }
496 
497 static
499 declare_parameter_helper(
500  const std::string & name,
501  rclcpp::ParameterType type,
502  const rclcpp::ParameterValue & default_value,
503  rcl_interfaces::msg::ParameterDescriptor parameter_descriptor,
504  bool ignore_override,
505  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
506  const std::map<std::string, rclcpp::ParameterValue> & overrides,
507  OnSetCallbacksHandleContainer & on_set_callback_container,
508  PostSetCallbacksHandleContainer & post_set_callback_container,
510  const std::string & combined_name,
512 {
513  // TODO(sloretz) parameter name validation
514  if (name.empty()) {
515  throw rclcpp::exceptions::InvalidParametersException("parameter name must not be empty");
516  }
517 
518  // Error if this parameter has already been declared and is different
519  if (__lockless_has_parameter(parameters, name)) {
521  "parameter '" + name + "' has already been declared");
522  }
523 
524  if (!parameter_descriptor.dynamic_typing) {
525  if (rclcpp::PARAMETER_NOT_SET == type) {
526  type = default_value.get_type();
527  }
528  if (rclcpp::PARAMETER_NOT_SET == type) {
530  name,
531  "cannot declare a statically typed parameter with an uninitialized value"
532  };
533  }
534  parameter_descriptor.type = static_cast<uint8_t>(type);
535  }
536 
537  rcl_interfaces::msg::ParameterEvent parameter_event;
538  auto result = __declare_parameter_common(
539  name,
540  default_value,
541  parameter_descriptor,
542  parameters,
543  overrides,
544  on_set_callback_container,
545  post_set_callback_container,
546  &parameter_event,
547  ignore_override);
548 
549  // If it failed to be set, then throw an exception.
550  if (!result.successful) {
551  constexpr const char type_error_msg_start[] = "Wrong parameter type";
552  if (
553  0u == std::strncmp(
554  result.reason.c_str(), type_error_msg_start, sizeof(type_error_msg_start) - 1))
555  {
556  // TODO(ivanpauno): Refactor the logic so we don't need the above `strncmp` and we can
557  // detect between both exceptions more elegantly.
558  throw rclcpp::exceptions::InvalidParameterTypeException(name, result.reason);
559  }
561  "parameter '" + name + "' could not be set: " + result.reason);
562  }
563 
564  // Publish if events_publisher_ is not nullptr, which may be if disabled in the constructor.
565  if (nullptr != events_publisher) {
566  parameter_event.node = combined_name;
567  parameter_event.stamp = node_clock.get_clock()->now();
568  events_publisher->publish(parameter_event);
569  }
570 
571  return parameters.at(name).value;
572 }
573 
576  const std::string & name,
577  const rclcpp::ParameterValue & default_value,
578  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
579  bool ignore_override)
580 {
581  std::lock_guard<std::recursive_mutex> lock(mutex_);
582  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
583 
584  return declare_parameter_helper(
585  name,
586  rclcpp::PARAMETER_NOT_SET,
587  default_value,
588  parameter_descriptor,
589  ignore_override,
590  parameters_,
591  parameter_overrides_,
592  on_set_parameters_callback_container_,
593  post_set_parameters_callback_container_,
594  events_publisher_.get(),
595  combined_name_,
596  *node_clock_);
597 }
598 
601  const std::string & name,
602  rclcpp::ParameterType type,
603  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
604  bool ignore_override)
605 {
606  std::lock_guard<std::recursive_mutex> lock(mutex_);
607  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
608 
609  if (rclcpp::PARAMETER_NOT_SET == type) {
610  throw std::invalid_argument{
611  "declare_parameter(): the provided parameter type cannot be rclcpp::PARAMETER_NOT_SET"};
612  }
613 
614  if (parameter_descriptor.dynamic_typing == true) {
615  throw std::invalid_argument{
616  "declare_parameter(): cannot declare parameter of specific type and pass descriptor"
617  "with `dynamic_typing=true`"};
618  }
619 
620  return declare_parameter_helper(
621  name,
622  type,
624  parameter_descriptor,
625  ignore_override,
626  parameters_,
627  parameter_overrides_,
628  on_set_parameters_callback_container_,
629  post_set_parameters_callback_container_,
630  events_publisher_.get(),
631  combined_name_,
632  *node_clock_);
633 }
634 
635 void
636 NodeParameters::undeclare_parameter(const std::string & name)
637 {
638  std::lock_guard<std::recursive_mutex> lock(mutex_);
639 
640  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
641 
642  auto parameter_info = parameters_.find(name);
643  if (parameter_info == parameters_.end()) {
645  "cannot undeclare parameter '" + name + "' which has not yet been declared");
646  }
647 
648  if (parameter_info->second.descriptor.read_only) {
650  "cannot undeclare parameter '" + name + "' because it is read-only");
651  }
652  if (!parameter_info->second.descriptor.dynamic_typing) {
654  name, "cannot undeclare a statically typed parameter"};
655  }
656 
657  parameters_.erase(parameter_info);
658 }
659 
660 bool
661 NodeParameters::has_parameter(const std::string & name) const
662 {
663  std::lock_guard<std::recursive_mutex> lock(mutex_);
664 
665  return __lockless_has_parameter(parameters_, name);
666 }
667 
668 std::vector<rcl_interfaces::msg::SetParametersResult>
669 NodeParameters::set_parameters(const std::vector<rclcpp::Parameter> & parameters)
670 {
671  std::vector<rcl_interfaces::msg::SetParametersResult> results;
672  results.reserve(parameters.size());
673 
674  for (const auto & p : parameters) {
675  auto result = set_parameters_atomically({{p}});
676  results.push_back(result);
677  }
678 
679  return results;
680 }
681 
682 template<typename ParameterVectorType>
683 auto
684 __find_parameter_by_name(
685  ParameterVectorType & parameters,
686  const std::string & name)
687 {
688  return std::find_if(
689  parameters.begin(),
690  parameters.end(),
691  [&](auto parameter) {return parameter.get_name() == name;});
692 }
693 
694 rcl_interfaces::msg::SetParametersResult
695 NodeParameters::set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters)
696 {
697  std::lock_guard<std::recursive_mutex> lock(mutex_);
698 
699  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
700 
701  rcl_interfaces::msg::SetParametersResult result;
702 
703  // call any user registered pre set parameter callbacks
704  // this callback can make changes to the original parameters list
705  // also check if the changed parameter list is empty or not, if empty return
706  std::vector<rclcpp::Parameter> parameters_after_pre_set_callback(parameters);
707  __call_pre_set_parameters_callbacks(
708  parameters_after_pre_set_callback,
709  pre_set_parameters_callback_container_);
710 
711  if (parameters_after_pre_set_callback.empty()) {
712  result.successful = false;
713  result.reason = "parameter list cannot be empty, this might be due to "
714  "pre_set_parameters_callback modifying the original parameters list.";
715  return result;
716  }
717 
718  // Check if any of the parameters are read-only, or if any parameters are not
719  // declared.
720  // If not declared, keep track of them in order to declare them later, when
721  // undeclared parameters are allowed, and if they're not allowed, fail.
722  std::vector<const rclcpp::Parameter *> parameters_to_be_declared;
723  for (const auto & parameter : parameters_after_pre_set_callback) {
724  const std::string & name = parameter.get_name();
725 
726  // Check to make sure the parameter name is valid.
727  if (name.empty()) {
728  throw rclcpp::exceptions::InvalidParametersException("parameter name must not be empty");
729  }
730 
731  // Check to see if it is declared.
732  auto parameter_info = parameters_.find(name);
733  if (parameter_info == parameters_.end()) {
734  // If not check to see if undeclared paramaters are allowed, ...
735  if (allow_undeclared_) {
736  // If so, mark the parameter to be declared for the user implicitly.
737  parameters_to_be_declared.push_back(&parameter);
738  // continue as it cannot be read-only, and because the declare will
739  // implicitly set the parameter and parameter_infos is for setting only.
740  continue;
741  } else {
742  // If not, then throw the exception as documented.
744  "parameter '" + name + "' cannot be set because it was not declared");
745  }
746  }
747 
748  // Check to see if it is read-only.
749  if (parameter_info->second.descriptor.read_only) {
750  result.successful = false;
751  result.reason = "parameter '" + name + "' cannot be set because it is read-only";
752  return result;
753  }
754  }
755 
756  // Declare parameters into a temporary "staging area", incase one of the declares fail.
757  // We will use the staged changes as input to the "set atomically" action.
758  // We explicitly avoid calling the user callbacks here, so that it may be called once, with
759  // all the other parameters to be set (already declared parameters).
760  std::map<std::string, rclcpp::node_interfaces::ParameterInfo> staged_parameter_changes;
761  rcl_interfaces::msg::ParameterEvent parameter_event_msg;
762  parameter_event_msg.node = combined_name_;
763  OnSetCallbacksHandleContainer empty_on_set_callback_container;
764  PostSetCallbacksHandleContainer empty_post_set_callback_container;
765 
766  // Implicit declare uses dynamic type descriptor.
767  rcl_interfaces::msg::ParameterDescriptor descriptor;
768  descriptor.dynamic_typing = true;
769  for (auto parameter_to_be_declared : parameters_to_be_declared) {
770  // This should not throw, because we validated the name and checked that
771  // the parameter was not already declared.
772  result = __declare_parameter_common(
773  parameter_to_be_declared->get_name(),
774  parameter_to_be_declared->get_parameter_value(),
775  descriptor,
776  staged_parameter_changes,
777  parameter_overrides_,
778  // Only call callbacks once below
779  empty_on_set_callback_container, // callback_container is explicitly empty
780  empty_post_set_callback_container, // callback_container is explicitly empty
781  &parameter_event_msg,
782  true);
783  if (!result.successful) {
784  // Declare failed, return knowing that nothing was changed because the
785  // staged changes were not applied.
786  return result;
787  }
788  }
789 
790  // If there were implicitly declared parameters, then we may need to copy the input parameters
791  // and then assign the value that was selected after the declare (could be affected by the
792  // initial parameter values).
793  const std::vector<rclcpp::Parameter> * parameters_to_be_set = &parameters_after_pre_set_callback;
794  std::vector<rclcpp::Parameter> parameters_copy;
795  if (0 != staged_parameter_changes.size()) { // If there were any implicitly declared parameters.
796  bool any_initial_values_used = false;
797  for (const auto & staged_parameter_change : staged_parameter_changes) {
798  auto it = __find_parameter_by_name(
799  parameters_after_pre_set_callback,
800  staged_parameter_change.first);
801  if (it->get_parameter_value() != staged_parameter_change.second.value) {
802  // In this case, the value of the staged parameter differs from the
803  // input from the user, and therefore we need to update things before setting.
804  any_initial_values_used = true;
805  // No need to search further since at least one initial value needs to be used.
806  break;
807  }
808  }
809  if (any_initial_values_used) {
810  parameters_copy = parameters_after_pre_set_callback;
811  for (const auto & staged_parameter_change : staged_parameter_changes) {
812  auto it = __find_parameter_by_name(parameters_copy, staged_parameter_change.first);
813  *it = Parameter(staged_parameter_change.first, staged_parameter_change.second.value);
814  }
815  parameters_to_be_set = &parameters_copy;
816  }
817  }
818 
819  // Collect parameters who will have had their type changed to
820  // rclcpp::PARAMETER_NOT_SET so they can later be implicitly undeclared.
821  std::vector<const rclcpp::Parameter *> parameters_to_be_undeclared;
822  for (const auto & parameter : *parameters_to_be_set) {
823  if (rclcpp::PARAMETER_NOT_SET == parameter.get_type()) {
824  auto it = parameters_.find(parameter.get_name());
825  if (it != parameters_.end() && rclcpp::PARAMETER_NOT_SET != it->second.value.get_type()) {
826  if (!it->second.descriptor.dynamic_typing) {
827  result.reason = "cannot undeclare a statically typed parameter";
828  result.successful = false;
829  return result;
830  }
831  parameters_to_be_undeclared.push_back(&parameter);
832  }
833  }
834  }
835 
836  // Set all of the parameters including the ones declared implicitly above.
837  result = __set_parameters_atomically_common(
838  // either the original parameters given by the user, or ones updated with initial values
839  *parameters_to_be_set,
840  // they are actually set on the official parameter storage
841  parameters_,
842  // These callbacks are called once. When a callback returns an unsuccessful result,
843  // the remaining aren't called
844  on_set_parameters_callback_container_,
845  post_set_parameters_callback_container_,
846  allow_undeclared_); // allow undeclared
847 
848  // If not successful, then stop here.
849  if (!result.successful) {
850  return result;
851  }
852 
853  // If successful, then update the parameter infos from the implicitly declared parameter's.
854  for (const auto & kv_pair : staged_parameter_changes) {
855  // assumption: the parameter is already present in parameters_ due to the above "set"
856  assert(__lockless_has_parameter(parameters_, kv_pair.first));
857  // assumption: the value in parameters_ is the same as the value resulting from the declare
858  assert(parameters_[kv_pair.first].value == kv_pair.second.value);
859  // This assignment should not change the name, type, or value, but may
860  // change other things from the ParameterInfo.
861  parameters_[kv_pair.first] = kv_pair.second;
862  }
863 
864  // Undeclare parameters that need to be.
865  for (auto parameter_to_undeclare : parameters_to_be_undeclared) {
866  auto it = parameters_.find(parameter_to_undeclare->get_name());
867  // assumption: the parameter to be undeclared should be in the parameter infos map
868  assert(it != parameters_.end());
869  if (it != parameters_.end()) {
870  // Update the parameter event message and remove it.
871  parameter_event_msg.deleted_parameters.push_back(
872  rclcpp::Parameter(it->first, it->second.value).to_parameter_msg());
873  parameters_.erase(it);
874  }
875  }
876 
877  // Update the parameter event message for any parameters which were only set,
878  // and not either declared or undeclared.
879  for (const auto & parameter : *parameters_to_be_set) {
880  if (staged_parameter_changes.find(parameter.get_name()) != staged_parameter_changes.end()) {
881  // This parameter was declared.
882  continue;
883  }
884  auto it = std::find_if(
885  parameters_to_be_undeclared.begin(),
886  parameters_to_be_undeclared.end(),
887  [&parameter](const auto & p) {return p->get_name() == parameter.get_name();});
888  if (it != parameters_to_be_undeclared.end()) {
889  // This parameter was undeclared (deleted).
890  continue;
891  }
892  // This parameter was neither declared nor undeclared.
893  parameter_event_msg.changed_parameters.push_back(parameter.to_parameter_msg());
894  }
895 
896  // Publish if events_publisher_ is not nullptr, which may be if disabled in the constructor.
897  if (nullptr != events_publisher_) {
898  parameter_event_msg.stamp = node_clock_->get_clock()->now();
899  events_publisher_->publish(parameter_event_msg);
900  }
901  return result;
902 }
903 
904 std::vector<rclcpp::Parameter>
905 NodeParameters::get_parameters(const std::vector<std::string> & names) const
906 {
907  std::vector<rclcpp::Parameter> results;
908  results.reserve(names.size());
909 
910  std::lock_guard<std::recursive_mutex> lock(mutex_);
911  for (auto & name : names) {
912  results.emplace_back(this->get_parameter(name));
913  }
914  return results;
915 }
916 
918 NodeParameters::get_parameter(const std::string & name) const
919 {
920  std::lock_guard<std::recursive_mutex> lock(mutex_);
921 
922  auto param_iter = parameters_.find(name);
923  if (parameters_.end() != param_iter) {
924  if (
925  param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET ||
926  param_iter->second.descriptor.dynamic_typing)
927  {
928  return rclcpp::Parameter{name, param_iter->second.value};
929  }
931  } else if (this->allow_undeclared_) {
932  return rclcpp::Parameter{name};
933  } else {
935  }
936 }
937 
938 bool
940  const std::string & name,
941  rclcpp::Parameter & parameter) const
942 {
943  std::lock_guard<std::recursive_mutex> lock(mutex_);
944 
945  auto param_iter = parameters_.find(name);
946  if (
947  parameters_.end() != param_iter &&
948  param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
949  {
950  parameter = {name, param_iter->second.value};
951  return true;
952  } else {
953  return false;
954  }
955 }
956 
957 bool
959  const std::string & prefix,
960  std::map<std::string, rclcpp::Parameter> & parameters) const
961 {
962  std::lock_guard<std::recursive_mutex> lock(mutex_);
963 
964  std::string prefix_with_dot = prefix.empty() ? prefix : prefix + ".";
965  bool ret = false;
966 
967  for (const auto & param : parameters_) {
968  if (param.first.find(prefix_with_dot) == 0 && param.first.length() > prefix_with_dot.length()) {
969  // Found one!
970  parameters[param.first.substr(prefix_with_dot.length())] = rclcpp::Parameter(param.second);
971  ret = true;
972  }
973  }
974 
975  return ret;
976 }
977 
978 std::vector<rcl_interfaces::msg::ParameterDescriptor>
979 NodeParameters::describe_parameters(const std::vector<std::string> & names) const
980 {
981  std::lock_guard<std::recursive_mutex> lock(mutex_);
982  std::vector<rcl_interfaces::msg::ParameterDescriptor> results;
983  results.reserve(names.size());
984 
985  for (const auto & name : names) {
986  auto it = parameters_.find(name);
987  if (it != parameters_.cend()) {
988  results.push_back(it->second.descriptor);
989  } else if (allow_undeclared_) {
990  // parameter not found, but undeclared allowed, so return empty
991  rcl_interfaces::msg::ParameterDescriptor default_description;
992  default_description.name = name;
993  results.push_back(default_description);
994  } else {
996  }
997  }
998 
999  if (results.size() != names.size()) {
1000  throw std::runtime_error("results and names unexpectedly different sizes");
1001  }
1002 
1003  return results;
1004 }
1005 
1006 std::vector<uint8_t>
1007 NodeParameters::get_parameter_types(const std::vector<std::string> & names) const
1008 {
1009  std::lock_guard<std::recursive_mutex> lock(mutex_);
1010  std::vector<uint8_t> results;
1011  results.reserve(names.size());
1012 
1013  for (const auto & name : names) {
1014  auto it = parameters_.find(name);
1015  if (it != parameters_.cend()) {
1016  results.push_back(it->second.value.get_type());
1017  } else if (allow_undeclared_) {
1018  // parameter not found, but undeclared allowed, so return not set
1019  results.push_back(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
1020  } else {
1022  }
1023  }
1024 
1025  if (results.size() != names.size()) {
1026  throw std::runtime_error("results and names unexpectedly different sizes");
1027  }
1028 
1029  return results;
1030 }
1031 
1032 rcl_interfaces::msg::ListParametersResult
1033 NodeParameters::list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const
1034 {
1035  std::lock_guard<std::recursive_mutex> lock(mutex_);
1036  rcl_interfaces::msg::ListParametersResult result;
1037 
1038  // TODO(mikaelarguedas) define parameter separator different from "/" to avoid ambiguity
1039  // using "." for now
1040  const char * separator = ".";
1041 
1042  auto separators_less_than_depth = [&depth, &separator](const std::string & str) -> bool {
1043  return static_cast<uint64_t>(std::count(str.begin(), str.end(), *separator)) < depth;
1044  };
1045 
1046  bool recursive = (prefixes.size() == 0) &&
1047  (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
1048 
1049  for (const std::pair<const std::string, ParameterInfo> & kv : parameters_) {
1050  if (!recursive) {
1051  bool get_all = (prefixes.size() == 0) && separators_less_than_depth(kv.first);
1052  if (!get_all) {
1053  bool prefix_matches = std::any_of(
1054  prefixes.cbegin(), prefixes.cend(),
1055  [&kv, &depth, &separator, &separators_less_than_depth](const std::string & prefix) {
1056  if (kv.first == prefix) {
1057  return true;
1058  } else if (kv.first.find(prefix + separator) == 0) {
1059  if (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) {
1060  return true;
1061  }
1062  std::string substr = kv.first.substr(prefix.length() + 1);
1063  return separators_less_than_depth(substr);
1064  }
1065  return false;
1066  });
1067 
1068  if (!prefix_matches) {
1069  continue;
1070  }
1071  }
1072  }
1073 
1074  result.names.push_back(kv.first);
1075  size_t last_separator = kv.first.find_last_of(separator);
1076  if (std::string::npos != last_separator) {
1077  std::string prefix = kv.first.substr(0, last_separator);
1078  if (
1079  std::find(result.prefixes.cbegin(), result.prefixes.cend(), prefix) ==
1080  result.prefixes.cend())
1081  {
1082  result.prefixes.push_back(prefix);
1083  }
1084  }
1085  }
1086  return result;
1087 }
1088 
1089 void
1091  const PreSetParametersCallbackHandle * const handle)
1092 {
1093  std::lock_guard<std::recursive_mutex> lock(mutex_);
1094  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
1095 
1096  auto it = std::find_if(
1097  pre_set_parameters_callback_container_.begin(),
1098  pre_set_parameters_callback_container_.end(),
1099  [handle](const auto & weak_handle) {
1100  return handle == weak_handle.lock().get();
1101  });
1102  if (it != pre_set_parameters_callback_container_.end()) {
1103  pre_set_parameters_callback_container_.erase(it);
1104  } else {
1105  throw std::runtime_error("Pre set parameter callback doesn't exist");
1106  }
1107 }
1108 
1109 void
1111  const OnSetParametersCallbackHandle * const handle)
1112 {
1113  std::lock_guard<std::recursive_mutex> lock(mutex_);
1114  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
1115 
1116  auto it = std::find_if(
1117  on_set_parameters_callback_container_.begin(),
1118  on_set_parameters_callback_container_.end(),
1119  [handle](const auto & weak_handle) {
1120  return handle == weak_handle.lock().get();
1121  });
1122  if (it != on_set_parameters_callback_container_.end()) {
1123  on_set_parameters_callback_container_.erase(it);
1124  } else {
1125  throw std::runtime_error("On set parameter callback doesn't exist");
1126  }
1127 }
1128 
1129 void
1131  const PostSetParametersCallbackHandle * const handle)
1132 {
1133  std::lock_guard<std::recursive_mutex> lock(mutex_);
1134  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
1135 
1136  auto it = std::find_if(
1137  post_set_parameters_callback_container_.begin(),
1138  post_set_parameters_callback_container_.end(),
1139  [handle](const auto & weak_handle) {
1140  return handle == weak_handle.lock().get();
1141  });
1142  if (it != post_set_parameters_callback_container_.end()) {
1143  post_set_parameters_callback_container_.erase(it);
1144  } else {
1145  throw std::runtime_error("Post set parameter callback doesn't exist");
1146  }
1147 }
1148 
1149 PreSetParametersCallbackHandle::SharedPtr
1150 NodeParameters::add_pre_set_parameters_callback(PreSetParametersCallbackType callback)
1151 {
1152  std::lock_guard<std::recursive_mutex> lock(mutex_);
1153  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
1154 
1155  auto handle = std::make_shared<PreSetParametersCallbackHandle>();
1156  handle->callback = callback;
1157  // the last callback registered is executed first.
1158  pre_set_parameters_callback_container_.emplace_front(handle);
1159  return handle;
1160 }
1161 
1162 OnSetParametersCallbackHandle::SharedPtr
1163 NodeParameters::add_on_set_parameters_callback(OnSetParametersCallbackType callback)
1164 {
1165  std::lock_guard<std::recursive_mutex> lock(mutex_);
1166  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
1167 
1168  auto handle = std::make_shared<OnSetParametersCallbackHandle>();
1169  handle->callback = callback;
1170  // the last callback registered is executed first.
1171  on_set_parameters_callback_container_.emplace_front(handle);
1172  return handle;
1173 }
1174 
1175 PostSetParametersCallbackHandle::SharedPtr
1177  PostSetParametersCallbackType callback)
1178 {
1179  std::lock_guard<std::recursive_mutex> lock(mutex_);
1180  ParameterMutationRecursionGuard guard(parameter_modification_enabled_);
1181 
1182  auto handle = std::make_shared<PostSetParametersCallbackHandle>();
1183  handle->callback = callback;
1184  // the last callback registered is executed first.
1185  post_set_parameters_callback_container_.emplace_front(handle);
1186  return handle;
1187 }
1188 
1189 const std::map<std::string, rclcpp::ParameterValue> &
1191 {
1192  return parameter_overrides_;
1193 }
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:81
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:242
Encapsulation of Quality of Service settings.
Definition: qos.hpp:116
Thrown if requested parameter type is invalid.
Definition: exceptions.hpp:262
Thrown if passed parameter value is invalid.
Definition: exceptions.hpp:251
Thrown if passed parameters are inconsistent or invalid.
Definition: exceptions.hpp:243
Thrown if parameter is already declared.
Definition: exceptions.hpp:294
Thrown if parameter is immutable and therefore cannot be undeclared.
Definition: exceptions.hpp:308
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
Definition: exceptions.hpp:301
Thrown when an uninitialized parameter is accessed.
Definition: exceptions.hpp:322
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 RCUTILS_WARN_UNUSED PostSetParametersCallbackHandle::SharedPtr add_post_set_parameters_callback(PostSetParametersCallbackType callback) override
Add a callback that gets triggered after parameters are set successfully.
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 RCUTILS_WARN_UNUSED OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnSetParametersCallbackType callback) override
Add a callback to validate parameters before they are set.
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 void remove_pre_set_parameters_callback(const PreSetParametersCallbackHandle *const handler) override
Remove a callback registered with add_pre_set_parameters_callback.
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 RCUTILS_WARN_UNUSED PreSetParametersCallbackHandle::SharedPtr add_pre_set_parameters_callback(PreSetParametersCallbackType callback) override
Add a callback that gets triggered before parameters are validated.
RCLCPP_PUBLIC rclcpp::Parameter get_parameter(const std::string &name) const override
Get the description of one parameter given a name.
RCLCPP_PUBLIC void remove_post_set_parameters_callback(const PostSetParametersCallbackHandle *const handler) override
Remove a callback registered with add_post_set_parameters_callback.
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:438
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:45
Non-templated part of PublisherOptionsWithAllocator<Allocator>.
Structure containing optional configuration for Publishers.
std::shared_ptr< Allocator > allocator
Optional custom allocator.
rcl_interfaces::msg::ParameterDescriptor descriptor
A description of the parameter.