rclcpp  master
C++ ROS Client Library API
parameter_value.hpp
Go to the documentation of this file.
1 // Copyright 2018 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_VALUE_HPP_
16 #define RCLCPP__PARAMETER_VALUE_HPP_
17 
18 #include <exception>
19 #include <iostream>
20 #include <ostream>
21 #include <sstream>
22 #include <string>
23 #include <vector>
24 
25 #include "rcl_interfaces/msg/parameter_type.hpp"
26 #include "rcl_interfaces/msg/parameter_value.hpp"
28 
29 namespace rclcpp
30 {
31 
32 enum ParameterType : uint8_t
33 {
44 };
45 
50 
54 
57 {
58 public:
60 
66  : std::runtime_error("expected [" + to_string(expected) + "] got [" + to_string(actual) + "]")
67  {}
68 };
69 
72 {
73 public:
79  explicit ParameterValue(const rcl_interfaces::msg::ParameterValue & value);
82  explicit ParameterValue(const bool bool_value);
85  explicit ParameterValue(const int int_value);
88  explicit ParameterValue(const int64_t int_value);
91  explicit ParameterValue(const float double_value);
94  explicit ParameterValue(const double double_value);
97  explicit ParameterValue(const std::string & string_value);
100  explicit ParameterValue(const char * string_value);
103  explicit ParameterValue(const std::vector<uint8_t> & byte_array_value);
106  explicit ParameterValue(const std::vector<bool> & bool_array_value);
109  explicit ParameterValue(const std::vector<int> & int_array_value);
112  explicit ParameterValue(const std::vector<int64_t> & int_array_value);
115  explicit ParameterValue(const std::vector<float> & double_array_value);
118  explicit ParameterValue(const std::vector<double> & double_array_value);
121  explicit ParameterValue(const std::vector<std::string> & string_array_value);
122 
126  get_type() const;
127 
130  rcl_interfaces::msg::ParameterValue
131  to_value_msg() const;
132 
135  bool
136  operator==(const ParameterValue & rhs) const;
137 
140  bool
141  operator!=(const ParameterValue & rhs) const;
142 
143  // The following get() variants require the use of ParameterType
144 
145  template<ParameterType type>
146  constexpr
148  get() const
149  {
152  }
153  return value_.bool_value;
154  }
155 
156  template<ParameterType type>
157  constexpr
159  get() const
160  {
163  }
164  return value_.integer_value;
165  }
166 
167  template<ParameterType type>
168  constexpr
170  get() const
171  {
174  }
175  return value_.double_value;
176  }
177 
178  template<ParameterType type>
179  constexpr
181  get() const
182  {
185  }
186  return value_.string_value;
187  }
188 
189  template<ParameterType type>
190  constexpr
191  typename std::enable_if<
193  get() const
194  {
197  }
198  return value_.byte_array_value;
199  }
200 
201  template<ParameterType type>
202  constexpr
203  typename std::enable_if<
205  get() const
206  {
209  }
210  return value_.bool_array_value;
211  }
212 
213  template<ParameterType type>
214  constexpr
215  typename std::enable_if<
217  get() const
218  {
221  }
222  return value_.integer_array_value;
223  }
224 
225  template<ParameterType type>
226  constexpr
227  typename std::enable_if<
229  get() const
230  {
233  }
234  return value_.double_array_value;
235  }
236 
237  template<ParameterType type>
238  constexpr
239  typename std::enable_if<
241  get() const
242  {
245  }
246  return value_.string_array_value;
247  }
248 
249  // The following get() variants allow the use of primitive types
250 
251  template<typename type>
252  constexpr
253  typename std::enable_if<std::is_same<type, bool>::value, const bool &>::type
254  get() const
255  {
256  return get<ParameterType::PARAMETER_BOOL>();
257  }
258 
259  template<typename type>
260  constexpr
261  typename std::enable_if<
263  get() const
264  {
265  return get<ParameterType::PARAMETER_INTEGER>();
266  }
267 
268  template<typename type>
269  constexpr
270  typename std::enable_if<std::is_floating_point<type>::value, const double &>::type
271  get() const
272  {
273  return get<ParameterType::PARAMETER_DOUBLE>();
274  }
275 
276  template<typename type>
277  constexpr
279  get() const
280  {
281  return get<ParameterType::PARAMETER_STRING>();
282  }
283 
284  template<typename type>
285  constexpr
286  typename std::enable_if<
288  type, const std::vector<uint8_t> &>::value, const std::vector<uint8_t> &>::type
289  get() const
290  {
291  return get<ParameterType::PARAMETER_BYTE_ARRAY>();
292  }
293 
294  template<typename type>
295  constexpr
296  typename std::enable_if<
298  type, const std::vector<bool> &>::value, const std::vector<bool> &>::type
299  get() const
300  {
301  return get<ParameterType::PARAMETER_BOOL_ARRAY>();
302  }
303 
304  template<typename type>
305  constexpr
306  typename std::enable_if<
308  type, const std::vector<int64_t> &>::value, const std::vector<int64_t> &>::type
309  get() const
310  {
311  return get<ParameterType::PARAMETER_INTEGER_ARRAY>();
312  }
313 
314  template<typename type>
315  constexpr
316  typename std::enable_if<
318  type, const std::vector<double> &>::value, const std::vector<double> &>::type
319  get() const
320  {
321  return get<ParameterType::PARAMETER_DOUBLE_ARRAY>();
322  }
323 
324  template<typename type>
325  constexpr
326  typename std::enable_if<
328  type, const std::vector<std::string> &>::value, const std::vector<std::string> &>::type
329  get() const
330  {
331  return get<ParameterType::PARAMETER_STRING_ARRAY>();
332  }
333 
334 private:
335  rcl_interfaces::msg::ParameterValue value_;
336 };
337 
341 to_string(const ParameterValue & type);
342 
343 } // namespace rclcpp
344 
345 #endif // RCLCPP__PARAMETER_VALUE_HPP_
rclcpp::PARAMETER_INTEGER_ARRAY
@ PARAMETER_INTEGER_ARRAY
Definition: parameter_value.hpp:41
rclcpp::ParameterValue::to_value_msg
rcl_interfaces::msg::ParameterValue to_value_msg() const
Return a message populated with the parameter value.
std::is_same
rclcpp::ParameterValue::ParameterValue
ParameterValue()
Construct a parameter value with type PARAMETER_NOT_SET.
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_convertible< type, const std::vector< int64_t > & >::value, const std::vector< int64_t > & >::type get() const
Definition: parameter_value.hpp:309
rclcpp::ParameterValue
Store the type and value of a parameter.
Definition: parameter_value.hpp:71
std::string
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_STRING_ARRAY, const std::vector< std::string > & >::type get() const
Definition: parameter_value.hpp:241
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_convertible< type, const std::vector< bool > & >::value, const std::vector< bool > & >::type get() const
Definition: parameter_value.hpp:299
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_floating_point< type >::value, const double & >::type get() const
Definition: parameter_value.hpp:271
rclcpp::operator<<
std::ostream & operator<<(std::ostream &os, const FutureReturnCode &future_return_code)
Stream operator for FutureReturnCode.
std::vector
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_STRING, const std::string & >::type get() const
Definition: parameter_value.hpp:181
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL_ARRAY, const std::vector< bool > & >::type get() const
Definition: parameter_value.hpp:205
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_BOOL, const bool & >::type get() const
Definition: parameter_value.hpp:148
rclcpp::PARAMETER_BYTE_ARRAY
@ PARAMETER_BYTE_ARRAY
Definition: parameter_value.hpp:39
rclcpp::PARAMETER_INTEGER
@ PARAMETER_INTEGER
Definition: parameter_value.hpp:36
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_DOUBLE, const double & >::type get() const
Definition: parameter_value.hpp:170
rclcpp::ParameterTypeException
Indicate the parameter type does not match the expected type.
Definition: parameter_value.hpp:56
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_convertible< type, const std::vector< std::string > & >::value, const std::vector< std::string > & >::type get() const
Definition: parameter_value.hpp:329
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_integral< type >::value &&!std::is_same< type, bool >::value, const int64_t & >::type get() const
Definition: parameter_value.hpp:263
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector< double > & >::type get() const
Definition: parameter_value.hpp:229
rclcpp::ParameterTypeException::ParameterTypeException
ParameterTypeException(ParameterType expected, ParameterType actual)
Construct an instance.
Definition: parameter_value.hpp:65
rclcpp::PARAMETER_DOUBLE_ARRAY
@ PARAMETER_DOUBLE_ARRAY
Definition: parameter_value.hpp:42
rclcpp
This header provides the get_node_base_interface() template function.
Definition: allocator_common.hpp:24
rclcpp::PARAMETER_STRING_ARRAY
@ PARAMETER_STRING_ARRAY
Definition: parameter_value.hpp:43
rclcpp::PARAMETER_STRING
@ PARAMETER_STRING
Definition: parameter_value.hpp:38
RCLCPP_PUBLIC
#define RCLCPP_PUBLIC
Definition: visibility_control.hpp:50
std::is_convertible
rclcpp::ParameterValue::get_type
ParameterType get_type() const
Return an enum indicating the type of the set value.
rclcpp::ParameterValue::operator!=
bool operator!=(const ParameterValue &rhs) const
Not equal operator.
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_convertible< type, std::string >::value, const std::string & >::type get() const
Definition: parameter_value.hpp:279
rclcpp::PARAMETER_DOUBLE
@ PARAMETER_DOUBLE
Definition: parameter_value.hpp:37
std::enable_if
std::ostream
rclcpp::PARAMETER_NOT_SET
@ PARAMETER_NOT_SET
Definition: parameter_value.hpp:34
std::runtime_error
std::is_integral
rclcpp::PARAMETER_BOOL
@ PARAMETER_BOOL
Definition: parameter_value.hpp:35
rclcpp::ParameterType
ParameterType
Definition: parameter_value.hpp:32
rclcpp::PARAMETER_BOOL_ARRAY
@ PARAMETER_BOOL_ARRAY
Definition: parameter_value.hpp:40
rclcpp::to_string
std::string to_string(const FutureReturnCode &future_return_code)
String conversion function for FutureReturnCode.
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_same< type, bool >::value, const bool & >::type get() const
Definition: parameter_value.hpp:254
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector< int64_t > & >::type get() const
Definition: parameter_value.hpp:217
visibility_control.hpp
std
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_INTEGER, const int64_t & >::type get() const
Definition: parameter_value.hpp:159
rclcpp::ParameterValue::operator==
bool operator==(const ParameterValue &rhs) const
Equal operator.
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_convertible< type, const std::vector< double > & >::value, const std::vector< double > & >::type get() const
Definition: parameter_value.hpp:319
rclcpp::ParameterValue::get
constexpr std::enable_if< std::is_convertible< type, const std::vector< uint8_t > & >::value, const std::vector< uint8_t > & >::type get() const
Definition: parameter_value.hpp:289
rclcpp::ParameterValue::get
constexpr std::enable_if< type==ParameterType::PARAMETER_BYTE_ARRAY, const std::vector< uint8_t > & >::type get() const
Definition: parameter_value.hpp:193