15 #include "rclcpp/node_interfaces/node_parameters.hpp"
17 #include <rcl_yaml_param_parser/parser.h>
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"
38 #include "../detail/resolve_parameter_overrides.hpp"
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,
50 const rcl_interfaces::msg::ParameterDescriptor &,
54 rcl_interfaces::msg::ParameterDescriptor descriptor;
55 descriptor.dynamic_typing =
true;
56 for (
const auto & pair : parameter_overrides) {
57 if (!has_parameter(pair.first)) {
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,
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)
85 using MessageT = rcl_interfaces::msg::ParameterEvent;
87 using AllocatorT = std::allocator<void>;
90 parameter_event_publisher_options);
91 publisher_options.
allocator = std::make_shared<AllocatorT>();
93 if (start_parameter_services) {
94 parameter_service_ = std::make_shared<ParameterService>(node_base, node_services,
this);
97 if (start_parameter_event_publisher) {
99 events_publisher_ = rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
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");
112 if (
nullptr == options) {
113 throw std::runtime_error(
"Need valid node options in NodeParameters");
118 auto context_ptr = node_base->get_context()->get_rcl_context();
119 global_args = &(context_ptr->global_arguments);
121 combined_name_ = node_base->get_fully_qualified_name();
123 parameter_overrides_ = rclcpp::detail::resolve_parameter_overrides(
124 combined_name_, parameter_overrides, &options->
arguments, global_args);
128 if (automatically_declare_parameters_from_overrides) {
129 using namespace std::placeholders;
130 local_perform_automatically_declare_parameters_from_overrides(
134 const std::string & name,
136 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
137 bool ignore_override)
140 name, default_value, parameter_descriptor, ignore_override);
147 NodeParameters::perform_automatically_declare_parameters_from_overrides()
149 local_perform_automatically_declare_parameters_from_overrides(
151 [
this](
const std::string & name) {
155 const std::string & name,
157 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
158 bool ignore_override)
161 name, default_value, parameter_descriptor, ignore_override);
166 NodeParameters::~NodeParameters()
171 __lockless_has_parameter(
172 const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
173 const std::string & name)
175 return parameters.find(name) != parameters.end();
181 __are_doubles_equal(
double x,
double y,
double ulp = 100.0)
183 return std::abs(x - y) <= std::numeric_limits<double>::epsilon() * std::abs(x + y) * ulp;
188 format_range_reason(
const std::string & name,
const char * range_type)
190 std::ostringstream ss;
191 ss <<
"Parameter {" << name <<
"} doesn't comply with " << range_type <<
" range.";
196 rcl_interfaces::msg::SetParametersResult
197 __check_parameter_value_in_range(
198 const rcl_interfaces::msg::ParameterDescriptor & descriptor,
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) {
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");
214 if (integer_range.step == 0) {
217 if (((v - integer_range.from_value) % integer_range.step) == 0) {
220 result.successful =
false;
221 result.reason = format_range_reason(descriptor.name,
"integer");
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)) {
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");
236 if (fp_range.step == 0.0) {
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)) {
243 result.successful =
false;
244 result.reason = format_range_reason(descriptor.name,
"floating point");
253 const std::string & name,
const std::string & old_type,
const std::string & new_type)
255 std::ostringstream ss;
258 ss <<
"Wrong parameter type, parameter {" << name <<
"} is of type {" << old_type <<
259 "}, setting it to {" << new_type <<
"} is not allowed.";
265 rcl_interfaces::msg::SetParametersResult
267 std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameter_infos,
268 const std::vector<rclcpp::Parameter> & parameters,
269 bool allow_undeclared)
271 rcl_interfaces::msg::SetParametersResult result;
272 result.successful =
true;
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;
282 descriptor.dynamic_typing =
true;
285 descriptor = parameter_infos[name].descriptor;
287 if (descriptor.name.empty()) {
288 descriptor.name = name;
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(
298 result = __check_parameter_value_in_range(
300 parameter.get_parameter_value());
301 if (!result.successful) {
308 using PreSetParametersCallbackType =
309 rclcpp::node_interfaces::NodeParametersInterface::PreSetParametersCallbackType;
312 using PreSetCallbacksHandleContainer =
313 rclcpp::node_interfaces::NodeParameters::PreSetCallbacksHandleContainer;
315 using OnSetParametersCallbackType =
316 rclcpp::node_interfaces::NodeParametersInterface::OnSetParametersCallbackType;
319 using OnSetCallbacksHandleContainer =
320 rclcpp::node_interfaces::NodeParameters::OnSetCallbacksHandleContainer;
322 using PostSetParametersCallbackType =
323 rclcpp::node_interfaces::NodeParametersInterface::PostSetParametersCallbackType;
326 using PostSetCallbacksHandleContainer =
327 rclcpp::node_interfaces::NodeParameters::PostSetCallbacksHandleContainer;
331 __call_pre_set_parameters_callbacks(
332 std::vector<rclcpp::Parameter> & parameters,
333 PreSetCallbacksHandleContainer & callback_container)
335 if (callback_container.empty()) {
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);
346 it = callback_container.erase(it);
352 rcl_interfaces::msg::SetParametersResult
353 __call_on_set_parameters_callbacks(
354 const std::vector<rclcpp::Parameter> & parameters,
355 OnSetCallbacksHandleContainer & callback_container)
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) {
369 it = callback_container.erase(it);
376 void __call_post_set_parameters_callbacks(
377 const std::vector<rclcpp::Parameter> & parameters,
378 PostSetCallbacksHandleContainer & callback_container)
380 if (callback_container.empty()) {
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);
391 it = callback_container.erase(it);
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)
406 rcl_interfaces::msg::SetParametersResult result = __check_parameters(
407 parameter_infos, parameters, allow_undeclared);
408 if (!result.successful) {
413 __call_on_set_parameters_callbacks(parameters, on_set_callback_container);
414 if (!result.successful) {
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();
426 __call_post_set_parameters_callbacks(parameters, post_set_callback_container);
434 rcl_interfaces::msg::SetParametersResult
435 __declare_parameter_common(
436 const std::string & name,
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)
447 std::map<std::string, ParameterInfo> parameter_infos {{name, ParameterInfo()}};
448 parameter_infos.at(name).
descriptor = parameter_descriptor;
452 auto overrides_it = overrides.find(name);
453 if (!ignore_override && overrides_it != overrides.end()) {
454 initial_value = &overrides_it->second;
458 if (initial_value->
get_type() == rclcpp::PARAMETER_NOT_SET) {
460 parameter_infos[name].descriptor.name = name;
461 if (parameter_descriptor.dynamic_typing) {
462 parameter_infos[name].descriptor.type = rclcpp::PARAMETER_NOT_SET;
464 parameter_infos[name].descriptor.type = parameter_descriptor.type;
466 parameters_out[name] = parameter_infos.at(name);
467 rcl_interfaces::msg::SetParametersResult result;
468 result.successful =
true;
473 std::vector<rclcpp::Parameter> parameter_wrappers {
rclcpp::Parameter(name, *initial_value)};
475 auto result = __set_parameters_atomically_common(
478 on_set_callback_container,
479 post_set_callback_container
482 if (!result.successful) {
487 parameters_out[name] = parameter_infos.at(name);
490 if (parameter_event_out) {
491 parameter_event_out->new_parameters.push_back(parameter_wrappers[0].to_parameter_msg());
499 declare_parameter_helper(
500 const std::string & name,
501 rclcpp::ParameterType type,
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,
519 if (__lockless_has_parameter(parameters, name)) {
521 "parameter '" + name +
"' has already been declared");
524 if (!parameter_descriptor.dynamic_typing) {
525 if (rclcpp::PARAMETER_NOT_SET == type) {
528 if (rclcpp::PARAMETER_NOT_SET == type) {
531 "cannot declare a statically typed parameter with an uninitialized value"
534 parameter_descriptor.type =
static_cast<uint8_t
>(type);
537 rcl_interfaces::msg::ParameterEvent parameter_event;
538 auto result = __declare_parameter_common(
541 parameter_descriptor,
544 on_set_callback_container,
545 post_set_callback_container,
550 if (!result.successful) {
551 constexpr
const char type_error_msg_start[] =
"Wrong parameter type";
554 result.reason.c_str(), type_error_msg_start,
sizeof(type_error_msg_start) - 1))
561 "parameter '" + name +
"' could not be set: " + result.reason);
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);
571 return parameters.at(name).value;
576 const std::string & name,
578 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
579 bool ignore_override)
581 std::lock_guard<std::recursive_mutex> lock(mutex_);
584 return declare_parameter_helper(
586 rclcpp::PARAMETER_NOT_SET,
588 parameter_descriptor,
591 parameter_overrides_,
592 on_set_parameters_callback_container_,
593 post_set_parameters_callback_container_,
594 events_publisher_.get(),
601 const std::string & name,
602 rclcpp::ParameterType type,
603 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
604 bool ignore_override)
606 std::lock_guard<std::recursive_mutex> lock(mutex_);
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"};
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`"};
620 return declare_parameter_helper(
624 parameter_descriptor,
627 parameter_overrides_,
628 on_set_parameters_callback_container_,
629 post_set_parameters_callback_container_,
630 events_publisher_.get(),
638 std::lock_guard<std::recursive_mutex> lock(mutex_);
642 auto parameter_info = parameters_.find(name);
643 if (parameter_info == parameters_.end()) {
645 "cannot undeclare parameter '" + name +
"' which has not yet been declared");
648 if (parameter_info->second.descriptor.read_only) {
650 "cannot undeclare parameter '" + name +
"' because it is read-only");
652 if (!parameter_info->second.descriptor.dynamic_typing) {
654 name,
"cannot undeclare a statically typed parameter"};
657 parameters_.erase(parameter_info);
663 std::lock_guard<std::recursive_mutex> lock(mutex_);
665 return __lockless_has_parameter(parameters_, name);
668 std::vector<rcl_interfaces::msg::SetParametersResult>
671 std::vector<rcl_interfaces::msg::SetParametersResult> results;
672 results.reserve(parameters.size());
674 for (
const auto & p : parameters) {
676 results.push_back(result);
682 template<
typename ParameterVectorType>
684 __find_parameter_by_name(
685 ParameterVectorType & parameters,
686 const std::string & name)
691 [&](
auto parameter) {return parameter.get_name() == name;});
694 rcl_interfaces::msg::SetParametersResult
697 std::lock_guard<std::recursive_mutex> lock(mutex_);
701 rcl_interfaces::msg::SetParametersResult result;
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_);
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.";
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();
732 auto parameter_info = parameters_.find(name);
733 if (parameter_info == parameters_.end()) {
735 if (allow_undeclared_) {
737 parameters_to_be_declared.push_back(¶meter);
744 "parameter '" + name +
"' cannot be set because it was not declared");
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";
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;
767 rcl_interfaces::msg::ParameterDescriptor descriptor;
768 descriptor.dynamic_typing =
true;
769 for (
auto parameter_to_be_declared : parameters_to_be_declared) {
772 result = __declare_parameter_common(
773 parameter_to_be_declared->get_name(),
774 parameter_to_be_declared->get_parameter_value(),
776 staged_parameter_changes,
777 parameter_overrides_,
779 empty_on_set_callback_container,
780 empty_post_set_callback_container,
781 ¶meter_event_msg,
783 if (!result.successful) {
793 const std::vector<rclcpp::Parameter> * parameters_to_be_set = ¶meters_after_pre_set_callback;
794 std::vector<rclcpp::Parameter> parameters_copy;
795 if (0 != staged_parameter_changes.size()) {
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) {
804 any_initial_values_used =
true;
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);
815 parameters_to_be_set = ¶meters_copy;
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;
831 parameters_to_be_undeclared.push_back(¶meter);
837 result = __set_parameters_atomically_common(
839 *parameters_to_be_set,
844 on_set_parameters_callback_container_,
845 post_set_parameters_callback_container_,
849 if (!result.successful) {
854 for (
const auto & kv_pair : staged_parameter_changes) {
856 assert(__lockless_has_parameter(parameters_, kv_pair.first));
858 assert(parameters_[kv_pair.first].value == kv_pair.second.value);
861 parameters_[kv_pair.first] = kv_pair.second;
865 for (
auto parameter_to_undeclare : parameters_to_be_undeclared) {
866 auto it = parameters_.find(parameter_to_undeclare->get_name());
868 assert(it != parameters_.end());
869 if (it != parameters_.end()) {
871 parameter_event_msg.deleted_parameters.push_back(
873 parameters_.erase(it);
879 for (
const auto & parameter : *parameters_to_be_set) {
880 if (staged_parameter_changes.find(parameter.get_name()) != staged_parameter_changes.end()) {
884 auto it = std::find_if(
885 parameters_to_be_undeclared.begin(),
886 parameters_to_be_undeclared.end(),
887 [¶meter](
const auto & p) {return p->get_name() == parameter.get_name();});
888 if (it != parameters_to_be_undeclared.end()) {
893 parameter_event_msg.changed_parameters.push_back(parameter.to_parameter_msg());
897 if (
nullptr != events_publisher_) {
898 parameter_event_msg.stamp = node_clock_->get_clock()->now();
899 events_publisher_->
publish(parameter_event_msg);
904 std::vector<rclcpp::Parameter>
907 std::vector<rclcpp::Parameter> results;
908 results.reserve(names.size());
910 std::lock_guard<std::recursive_mutex> lock(mutex_);
911 for (
auto & name : names) {
920 std::lock_guard<std::recursive_mutex> lock(mutex_);
922 auto param_iter = parameters_.find(name);
923 if (parameters_.end() != param_iter) {
925 param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET ||
926 param_iter->second.descriptor.dynamic_typing)
931 }
else if (this->allow_undeclared_) {
940 const std::string & name,
943 std::lock_guard<std::recursive_mutex> lock(mutex_);
945 auto param_iter = parameters_.find(name);
947 parameters_.end() != param_iter &&
948 param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
950 parameter = {name, param_iter->second.value};
959 const std::string & prefix,
960 std::map<std::string, rclcpp::Parameter> & parameters)
const
962 std::lock_guard<std::recursive_mutex> lock(mutex_);
964 std::string prefix_with_dot = prefix.empty() ? prefix : prefix +
".";
967 for (
const auto & param : parameters_) {
968 if (param.first.find(prefix_with_dot) == 0 && param.first.length() > prefix_with_dot.length()) {
970 parameters[param.first.substr(prefix_with_dot.length())] =
rclcpp::Parameter(param.second);
978 std::vector<rcl_interfaces::msg::ParameterDescriptor>
979 NodeParameters::describe_parameters(
const std::vector<std::string> & names)
const
981 std::lock_guard<std::recursive_mutex> lock(mutex_);
982 std::vector<rcl_interfaces::msg::ParameterDescriptor> results;
983 results.reserve(names.size());
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_) {
991 rcl_interfaces::msg::ParameterDescriptor default_description;
992 default_description.name = name;
993 results.push_back(default_description);
999 if (results.size() != names.size()) {
1000 throw std::runtime_error(
"results and names unexpectedly different sizes");
1006 std::vector<uint8_t>
1007 NodeParameters::get_parameter_types(
const std::vector<std::string> & names)
const
1009 std::lock_guard<std::recursive_mutex> lock(mutex_);
1010 std::vector<uint8_t> results;
1011 results.reserve(names.size());
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_) {
1019 results.push_back(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
1025 if (results.size() != names.size()) {
1026 throw std::runtime_error(
"results and names unexpectedly different sizes");
1032 rcl_interfaces::msg::ListParametersResult
1033 NodeParameters::list_parameters(
const std::vector<std::string> & prefixes, uint64_t depth)
const
1035 std::lock_guard<std::recursive_mutex> lock(mutex_);
1036 rcl_interfaces::msg::ListParametersResult result;
1040 const char * separator =
".";
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;
1046 bool recursive = (prefixes.size() == 0) &&
1047 (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE);
1049 for (
const std::pair<const std::string, ParameterInfo> & kv : parameters_) {
1051 bool get_all = (prefixes.size() == 0) && separators_less_than_depth(kv.first);
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) {
1058 }
else if (kv.first.find(prefix + separator) == 0) {
1059 if (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) {
1062 std::string substr = kv.first.substr(prefix.length() + 1);
1063 return separators_less_than_depth(substr);
1068 if (!prefix_matches) {
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);
1079 std::find(result.prefixes.cbegin(), result.prefixes.cend(), prefix) ==
1080 result.prefixes.cend())
1082 result.prefixes.push_back(prefix);
1093 std::lock_guard<std::recursive_mutex> lock(mutex_);
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();
1102 if (it != pre_set_parameters_callback_container_.end()) {
1103 pre_set_parameters_callback_container_.erase(it);
1105 throw std::runtime_error(
"Pre set parameter callback doesn't exist");
1113 std::lock_guard<std::recursive_mutex> lock(mutex_);
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();
1122 if (it != on_set_parameters_callback_container_.end()) {
1123 on_set_parameters_callback_container_.erase(it);
1125 throw std::runtime_error(
"On set parameter callback doesn't exist");
1133 std::lock_guard<std::recursive_mutex> lock(mutex_);
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();
1142 if (it != post_set_parameters_callback_container_.end()) {
1143 post_set_parameters_callback_container_.erase(it);
1145 throw std::runtime_error(
"Post set parameter callback doesn't exist");
1149 PreSetParametersCallbackHandle::SharedPtr
1152 std::lock_guard<std::recursive_mutex> lock(mutex_);
1155 auto handle = std::make_shared<PreSetParametersCallbackHandle>();
1156 handle->callback = callback;
1158 pre_set_parameters_callback_container_.emplace_front(handle);
1162 OnSetParametersCallbackHandle::SharedPtr
1165 std::lock_guard<std::recursive_mutex> lock(mutex_);
1168 auto handle = std::make_shared<OnSetParametersCallbackHandle>();
1169 handle->callback = callback;
1171 on_set_parameters_callback_container_.emplace_front(handle);
1175 PostSetParametersCallbackHandle::SharedPtr
1177 PostSetParametersCallbackType callback)
1179 std::lock_guard<std::recursive_mutex> lock(mutex_);
1182 auto handle = std::make_shared<PostSetParametersCallbackHandle>();
1183 handle->callback = callback;
1185 post_set_parameters_callback_container_.emplace_front(handle);
1189 const std::map<std::string, rclcpp::ParameterValue> &
1192 return parameter_overrides_;
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.
RCLCPP_PUBLIC rcl_interfaces::msg::Parameter to_parameter_msg() const
Convert the class in a parameter message.
A publisher publishes messages of any type to a topic.
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.
Encapsulation of Quality of Service settings.
Thrown if requested parameter type is invalid.
Thrown if passed parameter value is invalid.
Thrown if passed parameters are inconsistent or invalid.
Thrown if parameter is already declared.
Thrown if parameter is immutable and therefore cannot be undeclared.
Thrown if parameter is not declared, e.g. either set or get was called without first declaring.
Thrown when an uninitialized parameter is accessed.
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 ¶meter_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 > ¶meters) 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 > ¶meters) 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 > ¶meters) 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.
Hold output of parsing command line arguments.
Structure which encapsulates the options for creating a rcl_node_t.
bool use_global_arguments
If false then only use arguments in this struct, otherwise use global arguments also.
rcl_arguments_t arguments
Command line arguments that apply only to this node.
Structure which encapsulates a ROS Node.
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.