rclcpp
master
C++ ROS Client Library API
|
Go to the documentation of this file.
15 #ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
16 #define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
23 #include "rcl_interfaces/msg/list_parameters_result.hpp"
24 #include "rcl_interfaces/msg/parameter_descriptor.hpp"
25 #include "rcl_interfaces/msg/set_parameters_result.hpp"
33 namespace node_interfaces
42 rcl_interfaces::msg::SetParametersResult(
48 #define RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE \
49 "declare_parameter() with only a name is deprecated and will be deleted in the future.\n" \
50 "If you want to declare a parameter that won't change type without a default value use:\n" \
51 "`node_params->declare_parameter(name, type)`, with e.g. type=rclcpp::PARAMETER_INTEGER.\n\n" \
52 "If you want to declare a parameter that can dynamically change type use:\n" \
54 "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
55 "descriptor.dynamic_typing = true;\n" \
56 "node_params->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
88 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
89 rcl_interfaces::msg::ParameterDescriptor(),
90 bool ignore_override =
false) = 0;
102 const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
103 rcl_interfaces::msg::ParameterDescriptor(),
104 bool ignore_override =
false) = 0;
139 rcl_interfaces::msg::SetParametersResult
205 rcl_interfaces::msg::ListParametersResult
216 OnSetParametersCallbackHandle::SharedPtr
238 #endif // RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
virtual bool get_parameters_by_prefix(const std::string &prefix, std::map< std::string, rclcpp::Parameter > ¶meters) const =0
Get all parameters that have the specified prefix into the parameters map.
virtual bool has_parameter(const std::string &name) const =0
Return true if the parameter has been declared, otherwise false.
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
#define RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE
Definition: node_parameters_interface.hpp:48
virtual std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const =0
#define RCLCPP_SMART_PTR_ALIASES_ONLY(...)
Definition: macros.hpp:66
virtual void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)=0
Remove a callback registered with add_on_set_parameters_callback.
virtual rclcpp::Parameter get_parameter(const std::string &name) const =0
Get the description of one parameter given a name.
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
virtual const rclcpp::ParameterValue & declare_parameter(const std::string &name)=0
Declare a parameter.
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Definition: node_parameters_interface.hpp:36
virtual rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const =0
virtual std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const =0
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
Pure virtual interface class for the NodeParameters part of the Node API.
Definition: node_parameters_interface.hpp:60
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::Parameter > &)> OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:43
virtual const std::map< std::string, rclcpp::ParameterValue > & get_parameter_overrides() const =0
Return the initial parameter values used by the NodeParameters to override default values.
virtual rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > ¶meters)=0
Set one or more parameters, all at once.
OnParametersSetCallbackType callback
Definition: node_parameters_interface.hpp:45
virtual std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > ¶meters)=0
Set one or more parameters, one at a time.
ParameterType
Definition: parameter_value.hpp:32
virtual void undeclare_parameter(const std::string &name)=0
Undeclare a parameter.
virtual std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const =0
Get descriptions of parameters given their names.
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
virtual OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)=0
Add a callback for when parameters are being set.
virtual ~NodeParametersInterface()=default