rclcpp  master
C++ ROS Client Library API
parameter.hpp
Go to the documentation of this file.
1 // Copyright 2015 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__PARAMETER_HPP_
16 #define RCLCPP__PARAMETER_HPP_
17 
18 #include <iostream>
19 #include <ostream>
20 #include <sstream>
21 #include <string>
22 #include <vector>
23 
24 #include "rcl_interfaces/msg/parameter.hpp"
25 #include "rclcpp/exceptions.hpp"
28 
29 namespace rclcpp
30 {
31 
32 class Parameter;
33 
34 namespace node_interfaces
35 {
36 struct ParameterInfo;
37 } // namespace node_interfaces
38 
39 namespace detail
40 {
41 
42 // This helper function is required because you cannot do specialization on a
43 // class method, so instead we specialize this template function and call it
44 // from the unspecialized, but dependent, class method.
45 template<typename T>
46 auto
47 get_value_helper(const rclcpp::Parameter * parameter);
48 
49 } // namespace detail
50 
52 class Parameter
53 {
54 public:
57  Parameter();
58 
61  explicit Parameter(const std::string & name);
62 
65  Parameter(const std::string & name, const ParameterValue & value);
66 
68  template<typename ValueTypeT>
69  Parameter(const std::string & name, ValueTypeT value)
70  : Parameter(name, ParameterValue(value))
71  {}
72 
74  explicit Parameter(const rclcpp::node_interfaces::ParameterInfo & parameter_info);
75 
78  bool
79  operator==(const Parameter & rhs) const;
80 
83  bool
84  operator!=(const Parameter & rhs) const;
85 
89  get_type() const;
90 
94  get_type_name() const;
95 
98  const std::string &
99  get_name() const;
100 
103  rcl_interfaces::msg::ParameterValue
104  get_value_message() const;
105 
108  const rclcpp::ParameterValue &
109  get_parameter_value() const;
110 
112 
115  template<ParameterType ParamT>
116  decltype(auto)
117  get_value() const
118  {
119  return value_.get<ParamT>();
120  }
121 
123  template<typename T>
124  decltype(auto)
125  get_value() const;
126 
128 
132  bool
133  as_bool() const;
134 
136 
140  int64_t
141  as_int() const;
142 
144 
148  double
149  as_double() const;
150 
152 
156  const std::string &
157  as_string() const;
158 
160 
164  const std::vector<uint8_t> &
165  as_byte_array() const;
166 
168 
172  const std::vector<bool> &
173  as_bool_array() const;
174 
176 
180  const std::vector<int64_t> &
181  as_integer_array() const;
182 
184 
188  const std::vector<double> &
189  as_double_array() const;
190 
192 
196  const std::vector<std::string> &
197  as_string_array() const;
198 
201  static Parameter
202  from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter);
203 
206  rcl_interfaces::msg::Parameter
207  to_parameter_msg() const;
208 
211  std::string
212  value_to_string() const;
213 
214 private:
215  std::string name_;
216  ParameterValue value_;
217 };
218 
221 std::string
222 _to_json_dict_entry(const Parameter & param);
223 
225 std::ostream &
226 operator<<(std::ostream & os, const rclcpp::Parameter & pv);
227 
229 std::ostream &
230 operator<<(std::ostream & os, const std::vector<Parameter> & parameters);
231 
232 namespace detail
233 {
234 
235 template<typename T>
236 auto
238 {
239  return parameter->get_parameter_value().get<T>();
240 }
241 
242 // Specialization allowing Parameter::get() to return a const ref to the parameter value object.
243 template<>
244 inline
245 auto
246 get_value_helper<rclcpp::ParameterValue>(const rclcpp::Parameter * parameter)
247 {
248  return parameter->get_parameter_value();
249 }
250 
251 // Specialization allowing Parameter::get() to return a const ref to the parameter itself.
252 template<>
253 inline
254 auto
255 get_value_helper<rclcpp::Parameter>(const rclcpp::Parameter * parameter)
256 {
257  // Use this lambda to ensure it's a const reference being returned (and not a copy).
258  auto type_enforcing_lambda =
259  [&parameter]() -> const rclcpp::Parameter & {
260  return *parameter;
261  };
262  return type_enforcing_lambda();
263 }
264 
265 } // namespace detail
266 
267 template<typename T>
268 decltype(auto)
269 Parameter::get_value() const
270 {
271  try {
272  // use the helper to specialize for the ParameterValue and Parameter cases.
273  return detail::get_value_helper<T>(this);
274  } catch (const ParameterTypeException & ex) {
275  throw exceptions::InvalidParameterTypeException(this->name_, ex.what());
276  }
277 }
278 
279 } // namespace rclcpp
280 
281 namespace std
282 {
283 
287 to_string(const rclcpp::Parameter & param);
288 
292 to_string(const std::vector<rclcpp::Parameter> & parameters);
293 
294 } // namespace std
295 
296 #endif // RCLCPP__PARAMETER_HPP_
exceptions.hpp
rclcpp::Parameter::as_string_array
const std::vector< std::string > & as_string_array() const
Get value of parameter as string array (vector<std::string>).
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
std::string
rclcpp::Parameter::as_bool
bool as_bool() const
Get value of parameter as boolean.
rclcpp::Parameter::get_value_message
rcl_interfaces::msg::ParameterValue get_value_message() const
Get value of parameter as a parameter message.
rclcpp::Parameter::get_type_name
std::string get_type_name() const
Get the type name of the parameter.
rclcpp::Parameter::as_int
int64_t as_int() const
Get value of parameter as integer.
rclcpp::Parameter::to_parameter_msg
rcl_interfaces::msg::Parameter to_parameter_msg() const
Convert the class in a parameter message.
rclcpp::node_interfaces::ParameterInfo
Definition: node_parameters.hpp:48
rclcpp::Parameter::as_integer_array
const std::vector< int64_t > & as_integer_array() const
Get value of parameter as integer array (vector<int64_t>).
std::vector< rclcpp::Parameter >
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
Definition: parameter_value.hpp:148
rclcpp::Parameter::as_bool_array
const std::vector< bool > & as_bool_array() const
Get value of parameter as bool array (vector<bool>).
rclcpp::Parameter::get_value
decltype(auto) get_value() const
Get value of parameter using rclcpp::ParameterType as template argument.
Definition: parameter.hpp:117
rclcpp::Parameter::get_type
ParameterType get_type() const
Get the type of the parameter.
rclcpp::Parameter::operator==
bool operator==(const Parameter &rhs) const
Equal operator.
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
rclcpp::Parameter::operator!=
bool operator!=(const Parameter &rhs) const
Not equal operator.
rclcpp::Parameter::as_double_array
const std::vector< double > & as_double_array() const
Get value of parameter as double array (vector<double>).
rclcpp::Parameter::from_parameter_msg
static Parameter from_parameter_msg(const rcl_interfaces::msg::Parameter &parameter)
Convert a parameter message in a Parameter class object.
rclcpp::Parameter::value_to_string
std::string value_to_string() const
Get value of parameter as a string.
parameter_value.hpp
rclcpp::Parameter::get_parameter_value
const rclcpp::ParameterValue & get_parameter_value() const
Get the internal storage for the parameter value.
rclcpp::Parameter::as_double
double as_double() const
Get value of parameter as double.
rclcpp::Parameter::as_string
const std::string & as_string() const
Get value of parameter as string.
rclcpp::Parameter::get_name
const std::string & get_name() const
Get the name of the parameter.
rclcpp::Parameter::Parameter
Parameter(const std::string &name, ValueTypeT value)
Construct with given name and given parameter value.
Definition: parameter.hpp:69
rclcpp::ParameterType
ParameterType
Definition: parameter_value.hpp:32
rclcpp::to_string
std::string to_string(const FutureReturnCode &future_return_code)
String conversion function for FutureReturnCode.
rclcpp::Parameter::as_byte_array
const std::vector< uint8_t > & as_byte_array() const
Get value of parameter as byte array (vector<uint8_t>).
visibility_control.hpp
std
rclcpp::Parameter::Parameter
Parameter()
Construct with an empty name and a parameter value of type rclcpp::PARAMETER_NOT_SET.
rclcpp::Parameter
Structure to store an arbitrary parameter with templated get/set methods.
Definition: parameter.hpp:52
rclcpp::detail::get_value_helper
auto get_value_helper(const rclcpp::Parameter *parameter)
Definition: parameter.hpp:237
rclcpp::_to_json_dict_entry
std::string _to_json_dict_entry(const Parameter &param)
Return a json encoded version of the parameter intended for a dict.