ros2_control - kilted
Loading...
Searching...
No Matches
hardware_info.hpp
1// Copyright 2020 ros2_control Development Team
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 HARDWARE_INTERFACE__HARDWARE_INFO_HPP_
16#define HARDWARE_INTERFACE__HARDWARE_INFO_HPP_
17
18#include <fmt/compile.h>
19
20#include <string>
21#include <unordered_map>
22#include <variant>
23#include <vector>
24
25#include "joint_limits/joint_limits.hpp"
26
27namespace hardware_interface
28{
34{
39 std::string name;
41 std::string min = "";
43 std::string max = "";
45 std::string initial_value = "";
47 std::string data_type = "double";
49 int size;
55 std::unordered_map<std::string, std::string> parameters;
56};
57
60{
61 std::size_t joint_index;
62 std::size_t mimicked_joint_index;
63 double multiplier = 1.0;
64 double offset = 0.0;
65};
66
69{
70 NOT_SET,
71 TRUE,
72 FALSE
73};
74
80{
82 std::string name;
84 std::string type;
85
87 MimicAttribute is_mimic = MimicAttribute::NOT_SET;
88
93 std::vector<InterfaceInfo> command_interfaces;
98 std::vector<InterfaceInfo> state_interfaces;
100 std::unordered_map<std::string, std::string> parameters;
101};
102
105{
106 std::string name;
107 std::vector<std::string> state_interfaces;
108 std::vector<std::string> command_interfaces;
109 std::string role;
110 double mechanical_reduction = 1.0;
111 double offset = 0.0;
112};
113
116{
117 std::string name;
118 std::vector<std::string> state_interfaces;
119 std::vector<std::string> command_interfaces;
120 std::string role;
121 double mechanical_reduction = 1.0;
122 double offset = 0.0;
123};
124
127{
128 std::string name;
129 std::string type;
130 std::vector<JointInfo> joints;
131 std::vector<ActuatorInfo> actuators;
133 std::unordered_map<std::string, std::string> parameters;
134};
135
140using HANDLE_DATATYPE = std::variant<
141 std::monostate, double, float, bool, uint8_t, int8_t, uint16_t, int16_t, uint32_t, int32_t>;
143{
144public:
145 enum Value : int8_t
146 {
147 UNKNOWN = -1,
148 DOUBLE,
149 FLOAT32,
150 BOOL,
151 UINT8,
152 INT8,
153 UINT16,
154 INT16,
155 UINT32,
156 INT32,
157 };
158
159 HandleDataType() = default;
160 constexpr HandleDataType(Value value) : value_(value) {} // NOLINT(runtime/explicit)
161 explicit HandleDataType(const std::string & data_type)
162 {
163 if (data_type == "double")
164 {
165 value_ = DOUBLE;
166 }
167 else if (data_type == "bool")
168 {
169 value_ = BOOL;
170 }
171 else if (data_type == "float32")
172 {
173 value_ = FLOAT32;
174 }
175 else if (data_type == "uint8")
176 {
177 value_ = UINT8;
178 }
179 else if (data_type == "int8")
180 {
181 value_ = INT8;
182 }
183 else if (data_type == "uint16")
184 {
185 value_ = UINT16;
186 }
187 else if (data_type == "int16")
188 {
189 value_ = INT16;
190 }
191 else if (data_type == "uint32")
192 {
193 value_ = UINT32;
194 }
195 else if (data_type == "int32")
196 {
197 value_ = INT32;
198 }
199 else
200 {
201 value_ = UNKNOWN;
202 }
203 }
204
205 operator Value() const { return value_; }
206
207 explicit operator bool() const = delete;
208
209 constexpr bool operator==(HandleDataType other) const { return value_ == other.value_; }
210 constexpr bool operator!=(HandleDataType other) const { return value_ != other.value_; }
211
212 constexpr bool operator==(Value other) const { return value_ == other; }
213 constexpr bool operator!=(Value other) const { return value_ != other; }
214
215 std::string to_string() const
216 {
217 switch (value_)
218 {
219 case DOUBLE:
220 return "double";
221 case BOOL:
222 return "bool";
223 case FLOAT32:
224 return "float32";
225 case UINT8:
226 return "uint8";
227 case INT8:
228 return "int8";
229 case UINT16:
230 return "uint16";
231 case INT16:
232 return "int16";
233 case UINT32:
234 return "uint32";
235 case INT32:
236 return "int32";
237 default:
238 return "unknown";
239 }
240 }
241
248 {
249 switch (value_)
250 {
251 case DOUBLE: // fallthrough
252 case FLOAT32: // fallthrough
253 case BOOL: // fallthrough
254 case UINT8: // fallthrough
255 case INT8: // fallthrough
256 case UINT16: // fallthrough
257 case INT16: // fallthrough
258 case UINT32: // fallthrough
259 case INT32:
260 return true;
261 default:
262 return false; // unknown type cannot be converted
263 }
264 }
265
273 double cast_to_double(const HANDLE_DATATYPE & value) const
274 {
275 switch (value_)
276 {
277 case DOUBLE:
278 return std::get<double>(value);
279 case FLOAT32:
280 return static_cast<double>(std::get<float>(value));
281 case BOOL:
282 return static_cast<double>(std::get<bool>(value));
283 case UINT8:
284 return static_cast<double>(std::get<uint8_t>(value));
285 case INT8:
286 return static_cast<double>(std::get<int8_t>(value));
287 case UINT16:
288 return static_cast<double>(std::get<uint16_t>(value));
289 case INT16:
290 return static_cast<double>(std::get<int16_t>(value));
291 case UINT32:
292 return static_cast<double>(std::get<uint32_t>(value));
293 case INT32:
294 return static_cast<double>(std::get<int32_t>(value));
295 default:
296 throw std::runtime_error(
297 fmt::format(FMT_COMPILE("Data type : '{}' cannot be casted to double."), to_string()));
298 }
299 }
300
301 HandleDataType from_string(const std::string & data_type) { return HandleDataType(data_type); }
302
303private:
304 Value value_ = UNKNOWN;
305};
306
312{
313 InterfaceDescription(const std::string & prefix_name_in, const InterfaceInfo & interface_info_in)
314 : prefix_name(prefix_name_in),
315 interface_info(interface_info_in),
317 {
318 }
319
323 std::string prefix_name;
324
329
333 std::string interface_name;
334
335 const std::string & get_prefix_name() const { return prefix_name; }
336
337 const std::string & get_interface_name() const { return interface_info.name; }
338
339 const std::string & get_name() const { return interface_name; }
340
341 const std::string & get_data_type_string() const { return interface_info.data_type; }
342
343 HandleDataType get_data_type() const { return HandleDataType(interface_info.data_type); }
344};
345
347{
351 std::string scheduling_policy = "synchronized";
353 std::vector<int> cpu_affinity_cores = {};
355 bool print_warnings = true;
356};
357
360{
362 std::string name;
364 std::string type;
366 std::string group;
368 unsigned int rw_rate;
371 // TODO(anyone): deprecate after branching for kilted
380 std::unordered_map<std::string, std::string> hardware_parameters;
385 std::vector<ComponentInfo> joints;
389 std::vector<MimicJoint> mimic_joints;
394 std::vector<ComponentInfo> sensors;
399 std::vector<ComponentInfo> gpios;
404 std::vector<TransmissionInfo> transmissions;
408 std::string original_xml;
412 std::unordered_map<std::string, joint_limits::JointLimits> limits;
413
419 std::unordered_map<std::string, joint_limits::SoftJointLimits> soft_limits;
420};
421
422} // namespace hardware_interface
423#endif // HARDWARE_INTERFACE__HARDWARE_INFO_HPP_
Definition hardware_info.hpp:143
bool is_castable_to_double() const
Check if the HandleDataType can be casted to double.
Definition hardware_info.hpp:247
double cast_to_double(const HANDLE_DATATYPE &value) const
Cast the given value to double.
Definition hardware_info.hpp:273
Definition actuator.hpp:22
MimicAttribute
This enum is used to store the mimic attribute of a joint.
Definition hardware_info.hpp:69
std::variant< std::monostate, double, float, bool, uint8_t, int8_t, uint16_t, int16_t, uint32_t, int32_t > HANDLE_DATATYPE
Definition hardware_info.hpp:141
Contains semantic info about a given actuator loaded from URDF for a transmission.
Definition hardware_info.hpp:116
Definition hardware_info.hpp:80
std::vector< InterfaceInfo > command_interfaces
Definition hardware_info.hpp:93
std::unordered_map< std::string, std::string > parameters
(Optional) Key-value pairs of component parameters, e.g. min/max values or serial number.
Definition hardware_info.hpp:100
std::vector< InterfaceInfo > state_interfaces
Definition hardware_info.hpp:98
std::string name
Name of the component.
Definition hardware_info.hpp:82
MimicAttribute is_mimic
Hold the value of the mimic attribute if given, NOT_SET otherwise.
Definition hardware_info.hpp:87
std::string type
Type of the component: sensor, joint, or GPIO.
Definition hardware_info.hpp:84
Definition hardware_info.hpp:347
bool print_warnings
Whether to print warnings when the async thread doesn't meet its deadline.
Definition hardware_info.hpp:355
std::string scheduling_policy
Scheduling policy for the async worker thread.
Definition hardware_info.hpp:351
int thread_priority
Thread priority for the async worker thread.
Definition hardware_info.hpp:349
std::vector< int > cpu_affinity_cores
CPU affinity cores for the async worker thread.
Definition hardware_info.hpp:353
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:360
std::string type
Type of the hardware: actuator, sensor or system.
Definition hardware_info.hpp:364
int thread_priority
Definition hardware_info.hpp:374
std::vector< MimicJoint > mimic_joints
Definition hardware_info.hpp:389
std::string hardware_plugin_name
Name of the pluginlib plugin of the hardware that will be loaded.
Definition hardware_info.hpp:378
std::unordered_map< std::string, joint_limits::JointLimits > limits
Definition hardware_info.hpp:412
HardwareAsyncParams async_params
Async Parameters.
Definition hardware_info.hpp:376
std::unordered_map< std::string, std::string > hardware_parameters
(Optional) Key-value pairs for hardware parameters.
Definition hardware_info.hpp:380
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:366
bool is_async
Component is async.
Definition hardware_info.hpp:370
std::unordered_map< std::string, joint_limits::SoftJointLimits > soft_limits
Definition hardware_info.hpp:419
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:399
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:385
std::string original_xml
Definition hardware_info.hpp:408
std::string name
Name of the hardware.
Definition hardware_info.hpp:362
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:394
std::vector< TransmissionInfo > transmissions
Definition hardware_info.hpp:404
unsigned int rw_rate
Component's read and write rates in Hz.
Definition hardware_info.hpp:368
Definition hardware_info.hpp:312
InterfaceInfo interface_info
Definition hardware_info.hpp:328
std::string interface_name
Definition hardware_info.hpp:333
std::string prefix_name
Definition hardware_info.hpp:323
Definition hardware_info.hpp:34
std::string max
(Optional) Maximal allowed values of the interface.
Definition hardware_info.hpp:43
std::string initial_value
(Optional) Initial value of the interface.
Definition hardware_info.hpp:45
std::string name
Definition hardware_info.hpp:39
int size
(Optional) If the handle is an array, the size of the array.
Definition hardware_info.hpp:49
std::string min
(Optional) Minimal allowed values of the interface.
Definition hardware_info.hpp:41
std::string data_type
(Optional) The datatype of the interface, e.g. "bool", "int".
Definition hardware_info.hpp:47
std::unordered_map< std::string, std::string > parameters
Definition hardware_info.hpp:55
bool enable_limits
(Optional) enable or disable the limits for the command interfaces
Definition hardware_info.hpp:51
Contains semantic info about a given joint loaded from URDF for a transmission.
Definition hardware_info.hpp:105
This structure stores information about a joint that is mimicking another joint.
Definition hardware_info.hpp:60
Contains semantic info about a given transmission loaded from URDF.
Definition hardware_info.hpp:127
std::unordered_map< std::string, std::string > parameters
(Optional) Key-value pairs of custom parameters
Definition hardware_info.hpp:133