ROS 2 rclcpp + rcl - humble  humble
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/visibility_control.hpp"
28 
29 namespace rclcpp
30 {
31 
32 enum ParameterType : uint8_t
33 {
34  PARAMETER_NOT_SET = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET,
35  PARAMETER_BOOL = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL,
36  PARAMETER_INTEGER = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER,
37  PARAMETER_DOUBLE = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE,
38  PARAMETER_STRING = rcl_interfaces::msg::ParameterType::PARAMETER_STRING,
39  PARAMETER_BYTE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY,
40  PARAMETER_BOOL_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY,
41  PARAMETER_INTEGER_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY,
42  PARAMETER_DOUBLE_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY,
43  PARAMETER_STRING_ARRAY = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY,
44 };
45 
47 RCLCPP_PUBLIC
48 std::string
49 to_string(ParameterType type);
50 
51 RCLCPP_PUBLIC
52 std::ostream &
53 operator<<(std::ostream & os, ParameterType type);
54 
56 class ParameterTypeException : public std::runtime_error
57 {
58 public:
60 
64  RCLCPP_PUBLIC
65  ParameterTypeException(ParameterType expected, ParameterType actual)
66  : std::runtime_error("expected [" + to_string(expected) + "] got [" + to_string(actual) + "]")
67  {}
68 };
69 
72 {
73 public:
75  RCLCPP_PUBLIC
78  RCLCPP_PUBLIC
79  explicit ParameterValue(const rcl_interfaces::msg::ParameterValue & value);
81  RCLCPP_PUBLIC
82  explicit ParameterValue(const bool bool_value);
84  RCLCPP_PUBLIC
85  explicit ParameterValue(const int int_value);
87  RCLCPP_PUBLIC
88  explicit ParameterValue(const int64_t int_value);
90  RCLCPP_PUBLIC
91  explicit ParameterValue(const float double_value);
93  RCLCPP_PUBLIC
94  explicit ParameterValue(const double double_value);
96  RCLCPP_PUBLIC
97  explicit ParameterValue(const std::string & string_value);
99  RCLCPP_PUBLIC
100  explicit ParameterValue(const char * string_value);
102  RCLCPP_PUBLIC
103  explicit ParameterValue(const std::vector<uint8_t> & byte_array_value);
105  RCLCPP_PUBLIC
106  explicit ParameterValue(const std::vector<bool> & bool_array_value);
108  RCLCPP_PUBLIC
109  explicit ParameterValue(const std::vector<int> & int_array_value);
111  RCLCPP_PUBLIC
112  explicit ParameterValue(const std::vector<int64_t> & int_array_value);
114  RCLCPP_PUBLIC
115  explicit ParameterValue(const std::vector<float> & double_array_value);
117  RCLCPP_PUBLIC
118  explicit ParameterValue(const std::vector<double> & double_array_value);
120  RCLCPP_PUBLIC
121  explicit ParameterValue(const std::vector<std::string> & string_array_value);
122 
124  RCLCPP_PUBLIC
125  ParameterType
126  get_type() const;
127 
129  RCLCPP_PUBLIC
130  rcl_interfaces::msg::ParameterValue
131  to_value_msg() const;
132 
134  RCLCPP_PUBLIC
135  bool
136  operator==(const ParameterValue & rhs) const;
137 
139  RCLCPP_PUBLIC
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
147  typename std::enable_if<type == ParameterType::PARAMETER_BOOL, const bool &>::type
148  get() const
149  {
150  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
151  throw ParameterTypeException(ParameterType::PARAMETER_BOOL, get_type());
152  }
153  return value_.bool_value;
154  }
155 
156  template<ParameterType type>
157  constexpr
158  typename std::enable_if<type == ParameterType::PARAMETER_INTEGER, const int64_t &>::type
159  get() const
160  {
161  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER) {
162  throw ParameterTypeException(ParameterType::PARAMETER_INTEGER, get_type());
163  }
164  return value_.integer_value;
165  }
166 
167  template<ParameterType type>
168  constexpr
169  typename std::enable_if<type == ParameterType::PARAMETER_DOUBLE, const double &>::type
170  get() const
171  {
172  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE) {
173  throw ParameterTypeException(ParameterType::PARAMETER_DOUBLE, get_type());
174  }
175  return value_.double_value;
176  }
177 
178  template<ParameterType type>
179  constexpr
180  typename std::enable_if<type == ParameterType::PARAMETER_STRING, const std::string &>::type
181  get() const
182  {
183  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING) {
184  throw ParameterTypeException(ParameterType::PARAMETER_STRING, get_type());
185  }
186  return value_.string_value;
187  }
188 
189  template<ParameterType type>
190  constexpr
191  typename std::enable_if<
192  type == ParameterType::PARAMETER_BYTE_ARRAY, const std::vector<uint8_t> &>::type
193  get() const
194  {
195  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY) {
196  throw ParameterTypeException(ParameterType::PARAMETER_BYTE_ARRAY, get_type());
197  }
198  return value_.byte_array_value;
199  }
200 
201  template<ParameterType type>
202  constexpr
203  typename std::enable_if<
204  type == ParameterType::PARAMETER_BOOL_ARRAY, const std::vector<bool> &>::type
205  get() const
206  {
207  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY) {
208  throw ParameterTypeException(ParameterType::PARAMETER_BOOL_ARRAY, get_type());
209  }
210  return value_.bool_array_value;
211  }
212 
213  template<ParameterType type>
214  constexpr
215  typename std::enable_if<
216  type == ParameterType::PARAMETER_INTEGER_ARRAY, const std::vector<int64_t> &>::type
217  get() const
218  {
219  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY) {
220  throw ParameterTypeException(ParameterType::PARAMETER_INTEGER_ARRAY, get_type());
221  }
222  return value_.integer_array_value;
223  }
224 
225  template<ParameterType type>
226  constexpr
227  typename std::enable_if<
228  type == ParameterType::PARAMETER_DOUBLE_ARRAY, const std::vector<double> &>::type
229  get() const
230  {
231  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY) {
232  throw ParameterTypeException(ParameterType::PARAMETER_DOUBLE_ARRAY, get_type());
233  }
234  return value_.double_array_value;
235  }
236 
237  template<ParameterType type>
238  constexpr
239  typename std::enable_if<
240  type == ParameterType::PARAMETER_STRING_ARRAY, const std::vector<std::string> &>::type
241  get() const
242  {
243  if (value_.type != rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY) {
244  throw ParameterTypeException(ParameterType::PARAMETER_STRING_ARRAY, get_type());
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<
262  std::is_integral<type>::value && !std::is_same<type, bool>::value, const int64_t &>::type
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
278  typename std::enable_if<std::is_convertible<type, std::string>::value, const std::string &>::type
279  get() const
280  {
281  return get<ParameterType::PARAMETER_STRING>();
282  }
283 
284  template<typename type>
285  constexpr
286  typename std::enable_if<
287  std::is_convertible<
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<
297  std::is_convertible<
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<
307  std::is_convertible<
308  type, const std::vector<int> &>::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<
317  std::is_convertible<
318  type, const std::vector<int64_t> &>::value, const std::vector<int64_t> &>::type
319  get() const
320  {
321  return get<ParameterType::PARAMETER_INTEGER_ARRAY>();
322  }
323 
324  template<typename type>
325  constexpr
326  typename std::enable_if<
327  std::is_convertible<
328  type, const std::vector<float> &>::value, const std::vector<double> &>::type
329  get() const
330  {
331  return get<ParameterType::PARAMETER_DOUBLE_ARRAY>();
332  }
333 
334  template<typename type>
335  constexpr
336  typename std::enable_if<
337  std::is_convertible<
338  type, const std::vector<double> &>::value, const std::vector<double> &>::type
339  get() const
340  {
341  return get<ParameterType::PARAMETER_DOUBLE_ARRAY>();
342  }
343 
344  template<typename type>
345  constexpr
346  typename std::enable_if<
347  std::is_convertible<
348  type, const std::vector<std::string> &>::value, const std::vector<std::string> &>::type
349  get() const
350  {
351  return get<ParameterType::PARAMETER_STRING_ARRAY>();
352  }
353 
354 private:
355  rcl_interfaces::msg::ParameterValue value_;
356 };
357 
359 RCLCPP_PUBLIC
360 std::string
361 to_string(const ParameterValue & type);
362 
363 } // namespace rclcpp
364 
365 #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.