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"
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,
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)
60 using MessageT = rcl_interfaces::msg::ParameterEvent;
62 using AllocatorT = std::allocator<void>;
65 parameter_event_publisher_options);
66 publisher_options.allocator = std::make_shared<AllocatorT>();
68 if (start_parameter_services) {
69 parameter_service_ = std::make_shared<ParameterService>(node_base, node_services,
this);
72 if (start_parameter_event_publisher) {
74 events_publisher_ = rclcpp::create_publisher<MessageT, AllocatorT, PublisherT>(
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");
87 if (
nullptr == options) {
88 throw std::runtime_error(
"Need valid node options in NodeParameters");
93 auto context_ptr = node_base->get_context()->get_rcl_context();
94 global_args = &(context_ptr->global_arguments);
96 combined_name_ = node_base->get_fully_qualified_name();
98 parameter_overrides_ = rclcpp::detail::resolve_parameter_overrides(
99 combined_name_, parameter_overrides, &options->
arguments, global_args);
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(
118 NodeParameters::~NodeParameters()
123 __lockless_has_parameter(
124 const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters,
125 const std::string & name)
127 return parameters.find(name) != parameters.end();
133 __are_doubles_equal(
double x,
double y,
double ulp = 100.0)
135 return std::abs(x - y) <= std::numeric_limits<double>::epsilon() * std::abs(x + y) * ulp;
140 format_range_reason(
const std::string & name,
const char * range_type)
142 std::ostringstream ss;
143 ss <<
"Parameter {" << name <<
"} doesn't comply with " << range_type <<
" range.";
148 rcl_interfaces::msg::SetParametersResult
149 __check_parameter_value_in_range(
150 const rcl_interfaces::msg::ParameterDescriptor & descriptor,
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) {
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");
166 if (integer_range.step == 0) {
169 if (((v - integer_range.from_value) % integer_range.step) == 0) {
172 result.successful =
false;
173 result.reason = format_range_reason(descriptor.name,
"integer");
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)) {
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");
188 if (fp_range.step == 0.0) {
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)) {
195 result.successful =
false;
196 result.reason = format_range_reason(descriptor.name,
"floating point");
205 const std::string & name,
const std::string & old_type,
const std::string & new_type)
207 std::ostringstream ss;
210 ss <<
"Wrong parameter type, parameter {" << name <<
"} is of type {" << old_type <<
211 "}, setting it to {" << new_type <<
"} is not allowed.";
217 rcl_interfaces::msg::SetParametersResult
219 std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameter_infos,
220 const std::vector<rclcpp::Parameter> & parameters,
221 bool allow_undeclared)
223 rcl_interfaces::msg::SetParametersResult result;
224 result.successful =
true;
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;
234 descriptor.dynamic_typing =
true;
237 descriptor = parameter_infos[name].descriptor;
239 if (descriptor.name.empty()) {
240 descriptor.name = name;
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(
250 result = __check_parameter_value_in_range(
252 parameter.get_parameter_value());
253 if (!result.successful) {
260 using OnParametersSetCallbackType =
261 rclcpp::node_interfaces::NodeParametersInterface::OnParametersSetCallbackType;
262 using CallbacksContainerType =
263 rclcpp::node_interfaces::NodeParameters::CallbacksContainerType;
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)
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) {
286 it = callback_container.erase(it);
290 result = callback(parameters);
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)
305 rcl_interfaces::msg::SetParametersResult result = __check_parameters(
306 parameter_infos, parameters, allow_undeclared);
307 if (!result.successful) {
312 __call_on_parameters_set_callbacks(parameters, callback_container, callback);
313 if (!result.successful) {
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();
331 rcl_interfaces::msg::SetParametersResult
332 __declare_parameter_common(
333 const std::string & name,
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)
344 std::map<std::string, ParameterInfo> parameter_infos {{name, ParameterInfo()}};
345 parameter_infos.at(name).
descriptor = parameter_descriptor;
349 auto overrides_it = overrides.find(name);
350 if (!ignore_override && overrides_it != overrides.end()) {
351 initial_value = &overrides_it->second;
355 if (initial_value->
get_type() == rclcpp::PARAMETER_NOT_SET) {
357 parameter_infos[name].descriptor.name = name;
358 if (parameter_descriptor.dynamic_typing) {
359 parameter_infos[name].descriptor.type = rclcpp::PARAMETER_NOT_SET;
361 parameter_infos[name].descriptor.type = parameter_descriptor.type;
363 parameters_out[name] = parameter_infos.at(name);
364 rcl_interfaces::msg::SetParametersResult result;
365 result.successful =
true;
370 std::vector<rclcpp::Parameter> parameter_wrappers {
rclcpp::Parameter(name, *initial_value)};
372 auto result = __set_parameters_atomically_common(
378 if (!result.successful) {
383 parameters_out[name] = parameter_infos.at(name);
386 if (parameter_event_out) {
387 parameter_event_out->new_parameters.push_back(parameter_wrappers[0].to_parameter_msg());
395 declare_parameter_helper(
396 const std::string & name,
397 rclcpp::ParameterType type,
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,
415 if (__lockless_has_parameter(parameters, name)) {
417 "parameter '" + name +
"' has already been declared");
420 if (!parameter_descriptor.dynamic_typing) {
421 if (rclcpp::PARAMETER_NOT_SET == type) {
424 if (rclcpp::PARAMETER_NOT_SET == type) {
427 "cannot declare a statically typed parameter with an uninitialized value"
430 parameter_descriptor.type =
static_cast<uint8_t
>(type);
433 rcl_interfaces::msg::ParameterEvent parameter_event;
434 auto result = __declare_parameter_common(
437 parameter_descriptor,
446 if (!result.successful) {
447 constexpr
const char type_error_msg_start[] =
"Wrong parameter type";
450 result.reason.c_str(), type_error_msg_start,
sizeof(type_error_msg_start) - 1))
457 "parameter '" + name +
"' could not be set: " + result.reason);
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);
467 return parameters.at(name).value;
472 const std::string & name,
474 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
475 bool ignore_override)
477 std::lock_guard<std::recursive_mutex> lock(mutex_);
480 return declare_parameter_helper(
482 rclcpp::PARAMETER_NOT_SET,
484 parameter_descriptor,
487 parameter_overrides_,
488 on_parameters_set_callback_container_,
489 on_parameters_set_callback_,
490 events_publisher_.get(),
497 const std::string & name,
498 rclcpp::ParameterType type,
499 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor,
500 bool ignore_override)
502 std::lock_guard<std::recursive_mutex> lock(mutex_);
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"};
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`"};
516 return declare_parameter_helper(
520 parameter_descriptor,
523 parameter_overrides_,
524 on_parameters_set_callback_container_,
525 on_parameters_set_callback_,
526 events_publisher_.get(),
534 std::lock_guard<std::recursive_mutex> lock(mutex_);
538 auto parameter_info = parameters_.find(name);
539 if (parameter_info == parameters_.end()) {
541 "cannot undeclare parameter '" + name +
"' which has not yet been declared");
544 if (parameter_info->second.descriptor.read_only) {
546 "cannot undeclare parameter '" + name +
"' because it is read-only");
548 if (!parameter_info->second.descriptor.dynamic_typing) {
550 name,
"cannot undeclare an statically typed parameter"};
553 parameters_.erase(parameter_info);
559 std::lock_guard<std::recursive_mutex> lock(mutex_);
561 return __lockless_has_parameter(parameters_, name);
564 std::vector<rcl_interfaces::msg::SetParametersResult>
567 std::vector<rcl_interfaces::msg::SetParametersResult> results;
568 results.reserve(parameters.size());
570 for (
const auto & p : parameters) {
572 results.push_back(result);
578 template<
typename ParameterVectorType>
580 __find_parameter_by_name(
581 ParameterVectorType & parameters,
582 const std::string & name)
587 [&](
auto parameter) {return parameter.get_name() == name;});
590 rcl_interfaces::msg::SetParametersResult
593 std::lock_guard<std::recursive_mutex> lock(mutex_);
597 rcl_interfaces::msg::SetParametersResult result;
603 std::vector<const rclcpp::Parameter *> parameters_to_be_declared;
604 for (
const auto & parameter : parameters) {
605 const std::string & name = parameter.get_name();
613 auto parameter_info = parameters_.find(name);
614 if (parameter_info == parameters_.end()) {
616 if (allow_undeclared_) {
618 parameters_to_be_declared.push_back(¶meter);
625 "parameter '" + name +
"' cannot be set because it was not declared");
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";
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;
647 rcl_interfaces::msg::ParameterDescriptor descriptor;
648 descriptor.dynamic_typing =
true;
649 for (
auto parameter_to_be_declared : parameters_to_be_declared) {
652 result = __declare_parameter_common(
653 parameter_to_be_declared->get_name(),
654 parameter_to_be_declared->get_parameter_value(),
656 staged_parameter_changes,
657 parameter_overrides_,
659 empty_callback_container,
661 ¶meter_event_msg,
663 if (!result.successful) {
673 const std::vector<rclcpp::Parameter> * parameters_to_be_set = ¶meters;
674 std::vector<rclcpp::Parameter> parameters_copy;
675 if (0 != staged_parameter_changes.size()) {
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) {
682 any_initial_values_used =
true;
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);
693 parameters_to_be_set = ¶meters_copy;
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;
709 parameters_to_be_undeclared.push_back(¶meter);
715 result = __set_parameters_atomically_common(
717 *parameters_to_be_set,
721 on_parameters_set_callback_container_,
724 on_parameters_set_callback_,
728 if (!result.successful) {
733 for (
const auto & kv_pair : staged_parameter_changes) {
735 assert(__lockless_has_parameter(parameters_, kv_pair.first));
737 assert(parameters_[kv_pair.first].value == kv_pair.second.value);
740 parameters_[kv_pair.first] = kv_pair.second;
744 for (
auto parameter_to_undeclare : parameters_to_be_undeclared) {
745 auto it = parameters_.find(parameter_to_undeclare->get_name());
747 assert(it != parameters_.end());
748 if (it != parameters_.end()) {
750 parameter_event_msg.deleted_parameters.push_back(
752 parameters_.erase(it);
758 for (
const auto & parameter : *parameters_to_be_set) {
759 if (staged_parameter_changes.find(parameter.get_name()) != staged_parameter_changes.end()) {
763 auto it = std::find_if(
764 parameters_to_be_undeclared.begin(),
765 parameters_to_be_undeclared.end(),
766 [¶meter](
const auto & p) {return p->get_name() == parameter.get_name();});
767 if (it != parameters_to_be_undeclared.end()) {
772 parameter_event_msg.changed_parameters.push_back(parameter.to_parameter_msg());
776 if (
nullptr != events_publisher_) {
777 parameter_event_msg.stamp = node_clock_->get_clock()->now();
778 events_publisher_->
publish(parameter_event_msg);
784 std::vector<rclcpp::Parameter>
787 std::lock_guard<std::recursive_mutex> lock(mutex_);
788 std::vector<rclcpp::Parameter> results;
789 results.reserve(names.size());
791 for (
auto & name : names) {
792 auto found_parameter = parameters_.find(name);
793 if (found_parameter != parameters_.cend()) {
795 results.emplace_back(name, found_parameter->second.value);
796 }
else if (this->allow_undeclared_) {
810 std::lock_guard<std::recursive_mutex> lock(mutex_);
812 auto param_iter = parameters_.find(name);
814 parameters_.end() != param_iter &&
815 (param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET ||
816 param_iter->second.descriptor.dynamic_typing))
819 }
else if (this->allow_undeclared_) {
821 }
else if (parameters_.end() == param_iter) {
830 const std::string & name,
833 std::lock_guard<std::recursive_mutex> lock(mutex_);
835 auto param_iter = parameters_.find(name);
837 parameters_.end() != param_iter &&
838 param_iter->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET)
840 parameter = {name, param_iter->second.value};
849 const std::string & prefix,
850 std::map<std::string, rclcpp::Parameter> & parameters)
const
852 std::lock_guard<std::recursive_mutex> lock(mutex_);
854 std::string prefix_with_dot = prefix.empty() ? prefix : prefix +
".";
857 for (
const auto & param : parameters_) {
858 if (param.first.find(prefix_with_dot) == 0 && param.first.length() > prefix_with_dot.length()) {
860 parameters[param.first.substr(prefix_with_dot.length())] =
rclcpp::Parameter(param.second);
868 std::vector<rcl_interfaces::msg::ParameterDescriptor>
869 NodeParameters::describe_parameters(
const std::vector<std::string> & names)
const
871 std::lock_guard<std::recursive_mutex> lock(mutex_);
872 std::vector<rcl_interfaces::msg::ParameterDescriptor> results;
873 results.reserve(names.size());
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_) {
881 rcl_interfaces::msg::ParameterDescriptor default_description;
882 default_description.name = name;
883 results.push_back(default_description);
889 if (results.size() != names.size()) {
890 throw std::runtime_error(
"results and names unexpectedly different sizes");
897 NodeParameters::get_parameter_types(
const std::vector<std::string> & names)
const
899 std::lock_guard<std::recursive_mutex> lock(mutex_);
900 std::vector<uint8_t> results;
901 results.reserve(names.size());
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_) {
909 results.push_back(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET);
915 if (results.size() != names.size()) {
916 throw std::runtime_error(
"results and names unexpectedly different sizes");
922 rcl_interfaces::msg::ListParametersResult
923 NodeParameters::list_parameters(
const std::vector<std::string> & prefixes, uint64_t depth)
const
925 std::lock_guard<std::recursive_mutex> lock(mutex_);
926 rcl_interfaces::msg::ListParametersResult result;
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) {
940 }
else if (kv.first.find(prefix + separator) == 0) {
941 size_t length = prefix.length();
942 std::string substr = kv.first.substr(length);
944 return (depth == rcl_interfaces::srv::ListParameters::Request::DEPTH_RECURSIVE) ||
945 (static_cast<uint64_t>(std::count(substr.begin(), substr.end(), *separator)) < depth);
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);
955 std::find(result.prefixes.cbegin(), result.prefixes.cend(), prefix) ==
956 result.prefixes.cend())
958 result.prefixes.push_back(prefix);
970 std::lock_guard<std::recursive_mutex> lock(mutex_);
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();
979 if (it != on_parameters_set_callback_container_.end()) {
980 on_parameters_set_callback_container_.erase(it);
982 throw std::runtime_error(
"Callback doesn't exist");
986 OnSetParametersCallbackHandle::SharedPtr
989 std::lock_guard<std::recursive_mutex> lock(mutex_);
992 auto handle = std::make_shared<OnSetParametersCallbackHandle>();
993 handle->callback = callback;
995 on_parameters_set_callback_container_.emplace_front(handle);
999 const std::map<std::string, rclcpp::ParameterValue> &
1002 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 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 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 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 > ¶meters) 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.
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.
rcl_interfaces::msg::ParameterDescriptor descriptor
A description of the parameter.