15 #ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ 16 #define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ 21 #include "rcl_interfaces/msg/list_parameters_result.hpp" 22 #include "rcl_interfaces/msg/parameter_descriptor.hpp" 23 #include "rcl_interfaces/msg/set_parameters_result.hpp" 31 namespace node_interfaces
42 std::vector<rcl_interfaces::msg::SetParametersResult>
44 const std::vector<rclcpp::parameter::ParameterVariant> & parameters) = 0;
48 rcl_interfaces::msg::SetParametersResult
50 const std::vector<rclcpp::parameter::ParameterVariant> & parameters) = 0;
54 std::vector<rclcpp::parameter::ParameterVariant>
66 const std::string & name,
71 std::vector<rcl_interfaces::msg::ParameterDescriptor>
81 rcl_interfaces::msg::ListParametersResult
82 list_parameters(
const std::vector<std::string> & prefixes, uint64_t depth)
const = 0;
85 std::function<rcl_interfaces::msg::SetParametersResult(
86 const std::vector<rclcpp::parameter::ParameterVariant> &)>;
97 #endif // RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_ virtual std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const =0
virtual std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::parameter::ParameterVariant > ¶meters)=0
#define RCLCPP_SMART_PTR_ALIASES_ONLY(...)
Definition: macros.hpp:66
Definition: allocator_common.hpp:24
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::parameter::ParameterVariant > &)> ParametersCallbackFunction
Definition: node_parameters_interface.hpp:86
virtual rclcpp::parameter::ParameterVariant get_parameter(const std::string &name) const =0
virtual void register_param_change_callback(ParametersCallbackFunction callback)=0
virtual std::vector< rclcpp::parameter::ParameterVariant > get_parameters(const std::vector< std::string > &names) const =0
virtual rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const =0
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
Definition: parameter.hpp:45
Pure virtual interface class for the NodeParameters part of the Node API.
Definition: node_parameters_interface.hpp:35
virtual std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const =0
virtual rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::parameter::ParameterVariant > ¶meters)=0