ROS 2 rclcpp + rcl - kilted  kilted
ROS 2 C++ Client Library with ROS Client Library
parameter_value.cpp
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 #include "rclcpp/parameter_value.hpp"
16 
17 #include <string>
18 #include <vector>
19 
20 using rclcpp::ParameterType;
22 
23 std::string
24 rclcpp::to_string(const ParameterType type)
25 {
26  switch (type) {
27  case ParameterType::PARAMETER_NOT_SET:
28  return "not set";
29  case ParameterType::PARAMETER_BOOL:
30  return "bool";
31  case ParameterType::PARAMETER_INTEGER:
32  return "integer";
33  case ParameterType::PARAMETER_DOUBLE:
34  return "double";
35  case ParameterType::PARAMETER_STRING:
36  return "string";
37  case ParameterType::PARAMETER_BYTE_ARRAY:
38  return "byte_array";
39  case ParameterType::PARAMETER_BOOL_ARRAY:
40  return "bool_array";
41  case ParameterType::PARAMETER_INTEGER_ARRAY:
42  return "integer_array";
43  case ParameterType::PARAMETER_DOUBLE_ARRAY:
44  return "double_array";
45  case ParameterType::PARAMETER_STRING_ARRAY:
46  return "string_array";
47  default:
48  return "unknown type";
49  }
50 }
51 
52 std::ostream &
53 rclcpp::operator<<(std::ostream & os, const ParameterType type)
54 {
55  os << rclcpp::to_string(type);
56  return os;
57 }
58 
59 template<typename ValType, typename PrintType = ValType>
60 std::string
61 array_to_string(
62  const std::vector<ValType> & array,
63  const std::ios::fmtflags format_flags = std::ios::dec)
64 {
65  std::stringstream type_array;
66  bool first_item = true;
67  type_array << "[";
68  type_array.setf(format_flags, std::ios_base::basefield | std::ios::boolalpha);
69  type_array << std::showbase;
70  for (const ValType & value : array) {
71  if (!first_item) {
72  type_array << ", ";
73  } else {
74  first_item = false;
75  }
76  type_array << static_cast<PrintType>(value);
77  }
78  type_array << "]";
79  return type_array.str();
80 }
81 
82 std::string
84 {
85  switch (value.get_type()) {
86  case ParameterType::PARAMETER_NOT_SET:
87  return "not set";
88  case ParameterType::PARAMETER_BOOL:
89  return value.get<bool>() ? "true" : "false";
90  case ParameterType::PARAMETER_INTEGER:
91  return std::to_string(value.get<int>());
92  case ParameterType::PARAMETER_DOUBLE:
93  return std::to_string(value.get<double>());
94  case ParameterType::PARAMETER_STRING:
95  return value.get<std::string>();
96  case ParameterType::PARAMETER_BYTE_ARRAY:
97  return array_to_string<uint8_t, int>(value.get<std::vector<uint8_t>>(), std::ios::hex);
98  case ParameterType::PARAMETER_BOOL_ARRAY:
99  return array_to_string(value.get<std::vector<bool>>(), std::ios::boolalpha);
100  case ParameterType::PARAMETER_INTEGER_ARRAY:
101  return array_to_string(value.get<std::vector<int64_t>>());
102  case ParameterType::PARAMETER_DOUBLE_ARRAY:
103  return array_to_string(value.get<std::vector<double>>());
104  case ParameterType::PARAMETER_STRING_ARRAY:
105  return array_to_string(value.get<std::vector<std::string>>());
106  default:
107  return "unknown type";
108  }
109 }
110 
111 ParameterValue::ParameterValue()
112 {
113  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET;
114 }
115 
116 ParameterValue::ParameterValue(const rcl_interfaces::msg::ParameterValue & value)
117 {
118  value_ = value;
119  switch (value.type) {
120  case PARAMETER_BOOL:
121  case PARAMETER_INTEGER:
122  case PARAMETER_DOUBLE:
123  case PARAMETER_STRING:
124  case PARAMETER_BYTE_ARRAY:
125  case PARAMETER_BOOL_ARRAY:
126  case PARAMETER_INTEGER_ARRAY:
127  case PARAMETER_DOUBLE_ARRAY:
128  case PARAMETER_STRING_ARRAY:
129  case PARAMETER_NOT_SET:
130  break;
131  default:
132  throw rclcpp::exceptions::UnknownTypeError(std::to_string(value.type));
133  }
134 }
135 
136 ParameterValue::ParameterValue(const bool bool_value)
137 {
138  value_.bool_value = bool_value;
139  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL;
140 }
141 
142 ParameterValue::ParameterValue(const int int_value)
143 {
144  value_.integer_value = int_value;
145  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
146 }
147 
148 ParameterValue::ParameterValue(const int64_t int_value)
149 {
150  value_.integer_value = int_value;
151  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
152 }
153 
154 ParameterValue::ParameterValue(const float double_value)
155 {
156  value_.double_value = static_cast<double>(double_value);
157  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
158 }
159 
160 ParameterValue::ParameterValue(const double double_value)
161 {
162  value_.double_value = double_value;
163  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
164 }
165 
166 ParameterValue::ParameterValue(const std::string & string_value)
167 {
168  value_.string_value = string_value;
169  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING;
170 }
171 
172 ParameterValue::ParameterValue(const char * string_value)
173 : ParameterValue(std::string(string_value))
174 {}
175 
176 ParameterValue::ParameterValue(const std::vector<uint8_t> & byte_array_value)
177 {
178  value_.byte_array_value = byte_array_value;
179  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY;
180 }
181 
182 ParameterValue::ParameterValue(const std::vector<bool> & bool_array_value)
183 {
184  value_.bool_array_value = bool_array_value;
185  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY;
186 }
187 
188 ParameterValue::ParameterValue(const std::vector<int> & int_array_value)
189 {
190  value_.integer_array_value.assign(int_array_value.cbegin(), int_array_value.cend());
191  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY;
192 }
193 
194 ParameterValue::ParameterValue(const std::vector<int64_t> & int_array_value)
195 {
196  value_.integer_array_value = int_array_value;
197  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY;
198 }
199 
200 ParameterValue::ParameterValue(const std::vector<float> & float_array_value)
201 {
202  value_.double_array_value.assign(float_array_value.cbegin(), float_array_value.cend());
203  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY;
204 }
205 
206 ParameterValue::ParameterValue(const std::vector<double> & double_array_value)
207 {
208  value_.double_array_value = double_array_value;
209  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY;
210 }
211 
212 ParameterValue::ParameterValue(const std::vector<std::string> & string_array_value)
213 {
214  value_.string_array_value = string_array_value;
215  value_.type = rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY;
216 }
217 
218 ParameterType
220 {
221  return static_cast<ParameterType>(value_.type);
222 }
223 
224 rcl_interfaces::msg::ParameterValue
226 {
227  return value_;
228 }
229 
230 bool
232 {
233  return this->value_ == rhs.value_;
234 }
235 
236 bool
238 {
239  return this->value_ != rhs.value_;
240 }
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.
Thrown when an unknown type is passed.
Definition: exceptions.hpp:220
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.