ROS 2 rclcpp + rcl - rolling
rolling-a919a6e5
ROS 2 C++ Client Library with ROS Client Library
|
Implementation of the NodeParameters part of the Node API. More...
#include <rclcpp/node_interfaces/node_parameters.hpp>
Public Types | |
using | PreSetCallbacksHandleContainer = std::list< PreSetParametersCallbackHandle::WeakPtr > |
using | OnSetCallbacksHandleContainer = std::list< OnSetParametersCallbackHandle::WeakPtr > |
using | PostSetCallbacksHandleContainer = std::list< PostSetParametersCallbackHandle::WeakPtr > |
using | CallbacksContainerType = OnSetCallbacksHandleContainer |
![]() | |
using | OnSetParametersCallbackType = OnSetParametersCallbackHandle::OnSetParametersCallbackType |
using | PostSetParametersCallbackType = PostSetParametersCallbackHandle::PostSetParametersCallbackType |
using | PreSetParametersCallbackType = PreSetParametersCallbackHandle::PreSetParametersCallbackType |
Public Member Functions | |
RCLCPP_PUBLIC | NodeParameters (const node_interfaces::NodeBaseInterface::SharedPtr node_base, const node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const node_interfaces::NodeTopicsInterface::SharedPtr node_topics, const node_interfaces::NodeServicesInterface::SharedPtr node_services, const node_interfaces::NodeClockInterface::SharedPtr node_clock, const std::vector< Parameter > ¶meter_overrides, bool start_parameter_services, bool start_parameter_event_publisher, const rclcpp::QoS ¶meter_event_qos, const rclcpp::PublisherOptionsBase ¶meter_event_publisher_options, bool allow_undeclared_parameters, bool automatically_declare_parameters_from_overrides) |
Constructor. More... | |
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. More... | |
RCLCPP_PUBLIC const rclcpp::ParameterValue & | declare_parameter (const std::string &name, rclcpp::ParameterType type, const rcl_interfaces::msg::ParameterDescriptor ¶meter_descriptor=rcl_interfaces::msg::ParameterDescriptor(), bool ignore_override=false) override |
Declare a parameter. More... | |
RCLCPP_PUBLIC void | undeclare_parameter (const std::string &name) override |
Undeclare a parameter. More... | |
RCLCPP_PUBLIC bool | has_parameter (const std::string &name) const override |
Return true if the parameter has been declared, otherwise false. More... | |
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. More... | |
RCLCPP_PUBLIC rcl_interfaces::msg::SetParametersResult | set_parameters_atomically (const std::vector< rclcpp::Parameter > ¶meters) override |
Set one or more parameters, all at once. More... | |
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 rclcpp::Parameter | get_parameter (const std::string &name) const override |
Get the description of one parameter given a name. | |
RCLCPP_PUBLIC bool | get_parameter (const std::string &name, rclcpp::Parameter ¶meter) const override |
Get the description of one parameter given a name. | |
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::ParameterDescriptor > | describe_parameters (const std::vector< std::string > &names) const override |
RCLCPP_PUBLIC std::vector< uint8_t > | get_parameter_types (const std::vector< std::string > &names) const override |
RCLCPP_PUBLIC rcl_interfaces::msg::ListParametersResult | list_parameters (const std::vector< std::string > &prefixes, uint64_t depth) const override |
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. More... | |
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. More... | |
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. More... | |
RCLCPP_PUBLIC void | remove_on_set_parameters_callback (const OnSetParametersCallbackHandle *const handler) override |
Remove a callback registered with add_on_set_parameters_callback . More... | |
RCLCPP_PUBLIC void | remove_post_set_parameters_callback (const PostSetParametersCallbackHandle *const handler) override |
Remove a callback registered with add_post_set_parameters_callback . More... | |
RCLCPP_PUBLIC void | remove_pre_set_parameters_callback (const PreSetParametersCallbackHandle *const handler) override |
Remove a callback registered with add_pre_set_parameters_callback . More... | |
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 | enable_parameter_modification () override |
Enable parameter modification recursively during parameter callbacks. More... | |
Protected Member Functions | |
RCLCPP_PUBLIC void | perform_automatically_declare_parameters_from_overrides () |
Implementation of the NodeParameters part of the Node API.
Definition at line 83 of file node_parameters.hpp.
NodeParameters::NodeParameters | ( | const node_interfaces::NodeBaseInterface::SharedPtr | node_base, |
const node_interfaces::NodeLoggingInterface::SharedPtr | node_logging, | ||
const node_interfaces::NodeTopicsInterface::SharedPtr | node_topics, | ||
const node_interfaces::NodeServicesInterface::SharedPtr | node_services, | ||
const node_interfaces::NodeClockInterface::SharedPtr | node_clock, | ||
const std::vector< Parameter > & | parameter_overrides, | ||
bool | start_parameter_services, | ||
bool | start_parameter_event_publisher, | ||
const rclcpp::QoS & | parameter_event_qos, | ||
const rclcpp::PublisherOptionsBase & | parameter_event_publisher_options, | ||
bool | allow_undeclared_parameters, | ||
bool | automatically_declare_parameters_from_overrides | ||
) |
Constructor.
If using automatically_declare_parameters_from_overrides, overrides of get_parameter_overrides(), has_parameter(), declare_parameter() will not be respected. If this is an issue, pass false for automatically_declare_parameters_from_overrides and invoke perform_automatically_declare_parameters_from_overrides() manually after construction.
Definition at line 67 of file node_parameters.cpp.
References rclcpp::PublisherOptionsWithAllocator< Allocator >::allocator, rcl_node_options_s::arguments, declare_parameter(), get_parameter_overrides(), has_parameter(), rcl_node_get_options(), and rcl_node_options_s::use_global_arguments.
|
overridevirtual |
Add a callback to validate parameters before they are set.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 1212 of file node_parameters.cpp.
|
overridevirtual |
Add a callback that gets triggered after parameters are set successfully.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 1225 of file node_parameters.cpp.
|
overridevirtual |
Add a callback that gets triggered before parameters are validated.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 1199 of file node_parameters.cpp.
|
overridevirtual |
Declare and initialize a parameter.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 624 of file node_parameters.cpp.
Referenced by NodeParameters().
|
overridevirtual |
Declare a parameter.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 649 of file node_parameters.cpp.
|
overridevirtual |
Enable parameter modification recursively during parameter callbacks.
This function is used to enable parameter modification during parameter callbacks.
There are times when it does not allow parameter modification, such as when the parameter callbacks are being called and tries to modify the parameters with set_parameter and declare_parameter to avoid recursive parameter modification. This is protected by rclcpp::node_interfaces::ParameterMutationRecursionGuard.
This function is explicitly called to allow the recursive parameter operation during parameter callbacks by the application. Once it is enabled, the next parameter operation set/declare/undeclare_parameter are allowed to execute in the parameter callback. But, no more further recursive operation is allowed, unless user application calls this API again.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 1245 of file node_parameters.cpp.
|
overridevirtual |
Return true if the parameter has been declared, otherwise false.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 710 of file node_parameters.cpp.
Referenced by NodeParameters().
|
overridevirtual |
Remove a callback registered with add_on_set_parameters_callback
.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 1159 of file node_parameters.cpp.
|
overridevirtual |
Remove a callback registered with add_post_set_parameters_callback
.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 1179 of file node_parameters.cpp.
|
overridevirtual |
Remove a callback registered with add_pre_set_parameters_callback
.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 1139 of file node_parameters.cpp.
|
overridevirtual |
Set one or more parameters, one at a time.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 718 of file node_parameters.cpp.
References set_parameters_atomically().
|
overridevirtual |
Set one or more parameters, all at once.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 744 of file node_parameters.cpp.
References rclcpp::Publisher< MessageT, AllocatorT >::publish(), and rclcpp::Parameter::to_parameter_msg().
Referenced by set_parameters().
|
overridevirtual |
Undeclare a parameter.
Implements rclcpp::node_interfaces::NodeParametersInterface.
Definition at line 685 of file node_parameters.cpp.