ROS 2 rclcpp + rcl - jazzy  jazzy
ROS 2 C++ Client Library with ROS Client Library
parameter_value.hpp
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"
27 #include "rclcpp/exceptions/exceptions.hpp"
28 #include "rclcpp/visibility_control.hpp"
29 
30 namespace rclcpp
31 {
32 
33 enum ParameterType : uint8_t
34 {
35  PARAMETER_NOT_SET = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET,
36  PARAMETER_BOOL = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL,
37  PARAMETER_INTEGER = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER,
38  PARAMETER_DOUBLE = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE,
39  PARAMETER_STRING = rcl_interfaces::msg::ParameterType::PARAMETER_STRING,
40  PARAMETER_BYTE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY,
41  PARAMETER_BOOL_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY,
42  PARAMETER_INTEGER_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY,
43  PARAMETER_DOUBLE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY,
44  PARAMETER_STRING_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY,
45 };
46 
48 RCLCPP_PUBLIC
49 std::string
50 to_string(ParameterType type);
51 
52 RCLCPP_PUBLIC
53 std::ostream &
54 operator<<(std::ostream & os, ParameterType type);
55 
57 class ParameterTypeException : public std::runtime_error
58 {
59 public:
61 
65  RCLCPP_PUBLIC
66  ParameterTypeException(ParameterType expected, ParameterType actual)
67  : std::runtime_error("expected [" + to_string(expected) + "] got [" + to_string(actual) + "]")
68  {}
69 };
70 
73 {
74 public:
76  RCLCPP_PUBLIC
79  RCLCPP_PUBLIC
80  explicit ParameterValue(const rcl_interfaces::msg::ParameterValue & value);
82  RCLCPP_PUBLIC
83  explicit ParameterValue(const bool bool_value);
85  RCLCPP_PUBLIC
86  explicit ParameterValue(const int int_value);
88  RCLCPP_PUBLIC
89  explicit ParameterValue(const int64_t int_value);
91  RCLCPP_PUBLIC
92  explicit ParameterValue(const float double_value);
94  RCLCPP_PUBLIC
95  explicit ParameterValue(const double double_value);
97  RCLCPP_PUBLIC
98  explicit ParameterValue(const std::string & string_value);
100  RCLCPP_PUBLIC
101  explicit ParameterValue(const char * string_value);
103  RCLCPP_PUBLIC
104  explicit ParameterValue(const std::vector<uint8_t> & byte_array_value);
106  RCLCPP_PUBLIC
107  explicit ParameterValue(const std::vector<bool> & bool_array_value);
109  RCLCPP_PUBLIC
110  explicit ParameterValue(const std::vector<int> & int_array_value);
112  RCLCPP_PUBLIC
113  explicit ParameterValue(const std::vector<int64_t> & int_array_value);
115  RCLCPP_PUBLIC
116  explicit ParameterValue(const std::vector<float> & double_array_value);
118  RCLCPP_PUBLIC
119  explicit ParameterValue(const std::vector<double> & double_array_value);
121  RCLCPP_PUBLIC
122  explicit ParameterValue(const std::vector<std::string> & string_array_value);
123 
125  RCLCPP_PUBLIC
126  ParameterType
127  get_type() const;
128 
130  RCLCPP_PUBLIC
131  rcl_interfaces::msg::ParameterValue
132  to_value_msg() const;
133 
135  RCLCPP_PUBLIC
136  bool
137  operator==(const ParameterValue & rhs) const;
138 
140  RCLCPP_PUBLIC
141  bool
142  operator!=(const ParameterValue & rhs) const;
143 
144  // The following get() variants require the use of ParameterType
145 
146  template<ParameterType type>
147  constexpr
148  typename std::enable_if<type == ParameterType::PARAMETER_BOOL, const bool &>::type
149  get() const
150  {
151  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
152  throw ParameterTypeException(ParameterType::PARAMETER_BOOL, get_type());
153  }
154  return value_.bool_value;
155  }
156 
157  template<ParameterType type>
158  constexpr
159  typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, const int64_t &>::type
160  get() const
161  {
162  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) {
163  throw ParameterTypeException(ParameterType::PARAMETER_INTEGER, get_type());
164  }
165  return value_.integer_value;
166  }
167 
168  template<ParameterType type>
169  constexpr
170  typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, const double &>::type
171  get() const
172  {
173  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
174  throw ParameterTypeException(ParameterType::PARAMETER_DOUBLE, get_type());
175  }
176  return value_.double_value;
177  }
178 
179  template<ParameterType type>
180  constexpr
181  typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::type
182  get() const
183  {
184  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING) {
185  throw ParameterTypeException(ParameterType::PARAMETER_STRING, get_type());
186  }
187  return value_.string_value;
188  }
189 
190  template<ParameterType type>
191  constexpr
192  typename std::enable_if<
193  type == ParameterType::PARAMETER_BYTE_ARRAY, const std::vector<uint8_t> &>::type
194  get() const
195  {
196  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY) {
197  throw ParameterTypeException(ParameterType::PARAMETER_BYTE_ARRAY, get_type());
198  }
199  return value_.byte_array_value;
200  }
201 
202  template<ParameterType type>
203  constexpr
204  typename std::enable_if<
205  type == ParameterType::PARAMETER_BOOL_ARRAY, const std::vector<bool> &>::type
206  get() const
207  {
208  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY) {
209  throw ParameterTypeException(ParameterType::PARAMETER_BOOL_ARRAY, get_type());
210  }
211  return value_.bool_array_value;
212  }
213 
214  template<ParameterType type>
215  constexpr
216  typename std::enable_if<
217  type == ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector<int64_t> &>::type
218  get() const
219  {
220  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY) {
221  throw ParameterTypeException(ParameterType::PARAMETER_INTEGER_ARRAY, get_type());
222  }
223  return value_.integer_array_value;
224  }
225 
226  template<ParameterType type>
227  constexpr
228  typename std::enable_if<
229  type == ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector<double> &>::type
230  get() const
231  {
232  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY) {
233  throw ParameterTypeException(ParameterType::PARAMETER_DOUBLE_ARRAY, get_type());
234  }
235  return value_.double_array_value;
236  }
237 
238  template<ParameterType type>
239  constexpr
240  typename std::enable_if<
241  type == ParameterType::PARAMETER_STRING_ARRAY, const std::vector<std::string> &>::type
242  get() const
243  {
244  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY) {
245  throw ParameterTypeException(ParameterType::PARAMETER_STRING_ARRAY, get_type());
246  }
247  return value_.string_array_value;
248  }
249 
250  // The following get() variants allow the use of primitive types
251 
252  template<typename type>
253  constexpr
254  typename std::enable_if<std::is_same<type, bool>::value, const bool &>::type
255  get() const
256  {
257  return get<ParameterType::PARAMETER_BOOL>();
258  }
259 
260  template<typename type>
261  constexpr
262  typename std::enable_if<
263  std::is_integral<type>::value && !std::is_same<type, bool>::value, const int64_t &>::type
264  get() const
265  {
266  return get<ParameterType::PARAMETER_INTEGER>();
267  }
268 
269  template<typename type>
270  constexpr
271  typename std::enable_if<std::is_floating_point<type>::value, const double &>::type
272  get() const
273  {
274  return get<ParameterType::PARAMETER_DOUBLE>();
275  }
276 
277  template<typename type>
278  constexpr
279  typename std::enable_if<std::is_convertible<type, std::string>::value, const std::string &>::type
280  get() const
281  {
282  return get<ParameterType::PARAMETER_STRING>();
283  }
284 
285  template<typename type>
286  constexpr
287  typename std::enable_if<
288  std::is_convertible<
289  type, const std::vector<uint8_t> &>::value, const std::vector<uint8_t> &>::type
290  get() const
291  {
292  return get<ParameterType::PARAMETER_BYTE_ARRAY>();
293  }
294 
295  template<typename type>
296  constexpr
297  typename std::enable_if<
298  std::is_convertible<
299  type, const std::vector<bool> &>::value, const std::vector<bool> &>::type
300  get() const
301  {
302  return get<ParameterType::PARAMETER_BOOL_ARRAY>();
303  }
304 
305  template<typename type>
306  constexpr
307  typename std::enable_if<
308  std::is_convertible<
309  type, const std::vector<int> &>::value, const std::vector<int64_t> &>::type
310  get() const
311  {
312  return get<ParameterType::PARAMETER_INTEGER_ARRAY>();
313  }
314 
315  template<typename type>
316  constexpr
317  typename std::enable_if<
318  std::is_convertible<
319  type, const std::vector<int64_t> &>::value, const std::vector<int64_t> &>::type
320  get() const
321  {
322  return get<ParameterType::PARAMETER_INTEGER_ARRAY>();
323  }
324 
325  template<typename type>
326  constexpr
327  typename std::enable_if<
328  std::is_convertible<
329  type, const std::vector<float> &>::value, const std::vector<double> &>::type
330  get() const
331  {
332  return get<ParameterType::PARAMETER_DOUBLE_ARRAY>();
333  }
334 
335  template<typename type>
336  constexpr
337  typename std::enable_if<
338  std::is_convertible<
339  type, const std::vector<double> &>::value, const std::vector<double> &>::type
340  get() const
341  {
342  return get<ParameterType::PARAMETER_DOUBLE_ARRAY>();
343  }
344 
345  template<typename type>
346  constexpr
347  typename std::enable_if<
348  std::is_convertible<
349  type, const std::vector<std::string> &>::value, const std::vector<std::string> &>::type
350  get() const
351  {
352  return get<ParameterType::PARAMETER_STRING_ARRAY>();
353  }
354 
355 private:
356  rcl_interfaces::msg::ParameterValue value_;
357 };
358 
360 RCLCPP_PUBLIC
361 std::string
362 to_string(const ParameterValue & type);
363 
364 } // namespace rclcpp
365 
366 #endif // RCLCPP__PARAMETER_VALUE_HPP_
Indicate the parameter type does not match the expected type.
RCLCPP_PUBLIC ParameterTypeException(ParameterType expected, ParameterType actual)
Construct an instance.
Store the type and value of a parameter.
RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue to_value_msg() const
Return a message populated with the parameter value.
RCLCPP_PUBLIC ParameterType get_type() const
Return an enum indicating the type of the set value.
RCLCPP_PUBLIC bool operator==(const ParameterValue &rhs) const
Equal operator.
RCLCPP_PUBLIC bool operator!=(const ParameterValue &rhs) const
Not equal operator.
RCLCPP_PUBLIC ParameterValue()
Construct a parameter value with type PARAMETER_NOT_SET.
Versions of rosidl_typesupport_cpp::get_message_type_support_handle that handle adapted types.
RCLCPP_PUBLIC std::string to_string(const FutureReturnCode &future_return_code)
String conversion function for FutureReturnCode.
RCLCPP_PUBLIC std::ostream & operator<<(std::ostream &os, const FutureReturnCode &future_return_code)
Stream operator for FutureReturnCode.