rclcpp  master
C++ ROS Client Library API
node_parameters_interface.hpp
Go to the documentation of this file.
1 // Copyright 2016 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
16 #define RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
17 
18 #include <map>
19 #include <memory>
20 #include <string>
21 #include <vector>
22 
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"
26 
27 #include "rclcpp/macros.hpp"
28 #include "rclcpp/parameter.hpp"
30 
31 namespace rclcpp
32 {
33 namespace node_interfaces
34 {
35 
37 {
39 
42  rcl_interfaces::msg::SetParametersResult(
44 
46 };
47 
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" \
53  "```\n" \
54  "rcl_interfaces::msg::ParameterDescriptor descriptor;\n" \
55  "descriptor.dynamic_typing = true;\n" \
56  "node_params->declare_parameter(name, rclcpp::ParameterValue{}, descriptor);\n" \
57  "```"
58 
61 {
62 public:
64 
66  virtual
67  ~NodeParametersInterface() = default;
68 
70 
74  virtual
76  declare_parameter(const std::string & name) = 0;
77 
79 
83  virtual
86  const std::string & name,
87  const rclcpp::ParameterValue & default_value,
88  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
89  rcl_interfaces::msg::ParameterDescriptor(),
90  bool ignore_override = false) = 0;
91 
93 
97  virtual
100  const std::string & name,
102  const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
103  rcl_interfaces::msg::ParameterDescriptor(),
104  bool ignore_override = false) = 0;
105 
107 
111  virtual
112  void
113  undeclare_parameter(const std::string & name) = 0;
114 
116 
120  virtual
121  bool
122  has_parameter(const std::string & name) const = 0;
123 
125 
129  virtual
131  set_parameters(const std::vector<rclcpp::Parameter> & parameters) = 0;
132 
134 
138  virtual
139  rcl_interfaces::msg::SetParametersResult
141  const std::vector<rclcpp::Parameter> & parameters) = 0;
142 
144  /*
145  * \param[in] names a list of parameter names to check.
146  * \return the list of parameters that were found.
147  * Any parameter not found is omitted from the returned list.
148  */
150  virtual
152  get_parameters(const std::vector<std::string> & names) const = 0;
153 
155  /*
156  * \param[in] name the name of the parameter to look for.
157  * \return the parameter if it exists on the node.
158  * \throws std::out_of_range if the parameter does not exist on the node.
159  */
161  virtual
163  get_parameter(const std::string & name) const = 0;
164 
166  /*
167  * \param[in] name the name of the parameter to look for.
168  * \param[out] parameter the description if parameter exists on the node.
169  * \return true if the parameter exists on the node, or
170  * \return false if the parameter does not exist.
171  */
173  virtual
174  bool
176  const std::string & name,
177  rclcpp::Parameter & parameter) const = 0;
178 
180  /*
181  * \param[in] prefix the name of the prefix to look for.
182  * \param[out] parameters a map of parameters that matched the prefix.
183  * \return true if any parameters with the prefix exists on the node, or
184  * \return false otherwise.
185  */
187  virtual
188  bool
190  const std::string & prefix,
191  std::map<std::string, rclcpp::Parameter> & parameters) const = 0;
192 
194  virtual
196  describe_parameters(const std::vector<std::string> & names) const = 0;
197 
199  virtual
201  get_parameter_types(const std::vector<std::string> & names) const = 0;
202 
204  virtual
205  rcl_interfaces::msg::ListParametersResult
206  list_parameters(const std::vector<std::string> & prefixes, uint64_t depth) const = 0;
207 
209 
211 
215  virtual
216  OnSetParametersCallbackHandle::SharedPtr
218 
220 
224  virtual
225  void
227 
230  virtual
232  get_parameter_overrides() const = 0;
233 };
234 
235 } // namespace node_interfaces
236 } // namespace rclcpp
237 
238 #endif // RCLCPP__NODE_INTERFACES__NODE_PARAMETERS_INTERFACE_HPP_
rclcpp::node_interfaces::NodeParametersInterface::get_parameters_by_prefix
virtual bool get_parameters_by_prefix(const std::string &prefix, std::map< std::string, rclcpp::Parameter > &parameters) const =0
Get all parameters that have the specified prefix into the parameters map.
rclcpp::node_interfaces::NodeParametersInterface::has_parameter
virtual bool has_parameter(const std::string &name) const =0
Return true if the parameter has been declared, otherwise false.
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
std::string
RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE
#define RCLCPP_INTERNAL_NODE_PARAMETERS_INTERFACE_DEPRECATE_DECLARE
Definition: node_parameters_interface.hpp:48
rclcpp::node_interfaces::NodeParametersInterface::describe_parameters
virtual std::vector< rcl_interfaces::msg::ParameterDescriptor > describe_parameters(const std::vector< std::string > &names) const =0
std::vector< rclcpp::Parameter >
RCLCPP_SMART_PTR_ALIASES_ONLY
#define RCLCPP_SMART_PTR_ALIASES_ONLY(...)
Definition: macros.hpp:66
rclcpp::node_interfaces::NodeParametersInterface::remove_on_set_parameters_callback
virtual void remove_on_set_parameters_callback(const OnSetParametersCallbackHandle *const handler)=0
Remove a callback registered with add_on_set_parameters_callback.
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::Parameter > &)>
rclcpp::node_interfaces::NodeParametersInterface::get_parameter
virtual rclcpp::Parameter get_parameter(const std::string &name) const =0
Get the description of one parameter given a name.
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::node_interfaces::NodeParametersInterface::declare_parameter
virtual const rclcpp::ParameterValue & declare_parameter(const std::string &name)=0
Declare a parameter.
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::node_interfaces::OnSetParametersCallbackHandle
Definition: node_parameters_interface.hpp:36
rclcpp::node_interfaces::NodeParametersInterface::list_parameters
virtual rcl_interfaces::msg::ListParametersResult list_parameters(const std::vector< std::string > &prefixes, uint64_t depth) const =0
rclcpp::node_interfaces::NodeParametersInterface::get_parameter_types
virtual std::vector< uint8_t > get_parameter_types(const std::vector< std::string > &names) const =0
RCLCPP_SMART_PTR_DEFINITIONS
#define RCLCPP_SMART_PTR_DEFINITIONS(...)
Definition: macros.hpp:36
macros.hpp
rclcpp::node_interfaces::NodeParametersInterface
Pure virtual interface class for the NodeParameters part of the Node API.
Definition: node_parameters_interface.hpp:60
rclcpp::node_interfaces::OnSetParametersCallbackHandle::OnParametersSetCallbackType
std::function< rcl_interfaces::msg::SetParametersResult(const std::vector< rclcpp::Parameter > &)> OnParametersSetCallbackType
Definition: node_parameters_interface.hpp:43
rclcpp::node_interfaces::NodeParametersInterface::get_parameter_overrides
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.
rclcpp::node_interfaces::NodeParametersInterface::set_parameters_atomically
virtual rcl_interfaces::msg::SetParametersResult set_parameters_atomically(const std::vector< rclcpp::Parameter > &parameters)=0
Set one or more parameters, all at once.
rclcpp::node_interfaces::OnSetParametersCallbackHandle::callback
OnParametersSetCallbackType callback
Definition: node_parameters_interface.hpp:45
std::map
rclcpp::node_interfaces::NodeParametersInterface::set_parameters
virtual std::vector< rcl_interfaces::msg::SetParametersResult > set_parameters(const std::vector< rclcpp::Parameter > &parameters)=0
Set one or more parameters, one at a time.
rclcpp::ParameterType
ParameterType
Definition: parameter_value.hpp:32
parameter.hpp
rclcpp::node_interfaces::NodeParametersInterface::undeclare_parameter
virtual void undeclare_parameter(const std::string &name)=0
Undeclare a parameter.
rclcpp::node_interfaces::NodeParametersInterface::get_parameters
virtual std::vector< rclcpp::Parameter > get_parameters(const std::vector< std::string > &names) const =0
Get descriptions of parameters given their names.
visibility_control.hpp
rclcpp::Parameter
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
rclcpp::node_interfaces::NodeParametersInterface::add_on_set_parameters_callback
virtual OnSetParametersCallbackHandle::SharedPtr add_on_set_parameters_callback(OnParametersSetCallbackType callback)=0
Add a callback for when parameters are being set.
rclcpp::node_interfaces::NodeParametersInterface::~NodeParametersInterface
virtual ~NodeParametersInterface()=default