ros2_control - rolling
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;
53 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
90 bool enable_limits = true;
91
96 std::vector<InterfaceInfo> command_interfaces;
101 std::vector<InterfaceInfo> state_interfaces;
103 std::unordered_map<std::string, std::string> parameters;
104};
105
108{
109 std::string name;
110 std::vector<std::string> state_interfaces;
111 std::vector<std::string> command_interfaces;
112 std::string role;
113 double mechanical_reduction = 1.0;
114 double offset = 0.0;
115};
116
119{
120 std::string name;
121 std::vector<std::string> state_interfaces;
122 std::vector<std::string> command_interfaces;
123 std::string role;
124 double mechanical_reduction = 1.0;
125 double offset = 0.0;
126};
127
130{
131 std::string name;
132 std::string type;
133 std::vector<JointInfo> joints;
134 std::vector<ActuatorInfo> actuators;
136 std::unordered_map<std::string, std::string> parameters;
137};
138
143using HANDLE_DATATYPE = std::variant<
144 std::monostate, double, float, bool, uint8_t, int8_t, uint16_t, int16_t, uint32_t, int32_t>;
146{
147public:
148 enum Value : int8_t
149 {
150 UNKNOWN = -1,
151 DOUBLE,
152 FLOAT32,
153 BOOL,
154 UINT8,
155 INT8,
156 UINT16,
157 INT16,
158 UINT32,
159 INT32,
160 };
161
162 HandleDataType() = default;
163 constexpr HandleDataType(Value value) : value_(value) {} // NOLINT(runtime/explicit)
164 explicit HandleDataType(const std::string & data_type)
165 {
166 if (data_type == "double")
167 {
168 value_ = DOUBLE;
169 }
170 else if (data_type == "bool")
171 {
172 value_ = BOOL;
173 }
174 else if (data_type == "float32")
175 {
176 value_ = FLOAT32;
177 }
178 else if (data_type == "uint8")
179 {
180 value_ = UINT8;
181 }
182 else if (data_type == "int8")
183 {
184 value_ = INT8;
185 }
186 else if (data_type == "uint16")
187 {
188 value_ = UINT16;
189 }
190 else if (data_type == "int16")
191 {
192 value_ = INT16;
193 }
194 else if (data_type == "uint32")
195 {
196 value_ = UINT32;
197 }
198 else if (data_type == "int32")
199 {
200 value_ = INT32;
201 }
202 else
203 {
204 value_ = UNKNOWN;
205 }
206 }
207
208 operator Value() const { return value_; }
209
210 explicit operator bool() const = delete;
211
212 constexpr bool operator==(HandleDataType other) const { return value_ == other.value_; }
213 constexpr bool operator!=(HandleDataType other) const { return value_ != other.value_; }
214
215 constexpr bool operator==(Value other) const { return value_ == other; }
216 constexpr bool operator!=(Value other) const { return value_ != other; }
217
218 std::string to_string() const
219 {
220 switch (value_)
221 {
222 case DOUBLE:
223 return "double";
224 case BOOL:
225 return "bool";
226 case FLOAT32:
227 return "float32";
228 case UINT8:
229 return "uint8";
230 case INT8:
231 return "int8";
232 case UINT16:
233 return "uint16";
234 case INT16:
235 return "int16";
236 case UINT32:
237 return "uint32";
238 case INT32:
239 return "int32";
240 default:
241 return "unknown";
242 }
243 }
244
251 {
252 switch (value_)
253 {
254 case DOUBLE: // fallthrough
255 case FLOAT32: // fallthrough
256 case BOOL: // fallthrough
257 case UINT8: // fallthrough
258 case INT8: // fallthrough
259 case UINT16: // fallthrough
260 case INT16: // fallthrough
261 case UINT32: // fallthrough
262 case INT32:
263 return true;
264 default:
265 return false; // unknown type cannot be converted
266 }
267 }
268
276 double cast_to_double(const HANDLE_DATATYPE & value) const
277 {
278 switch (value_)
279 {
280 case DOUBLE:
281 return std::get<double>(value);
282 case FLOAT32:
283 return static_cast<double>(std::get<float>(value));
284 case BOOL:
285 return static_cast<double>(std::get<bool>(value));
286 case UINT8:
287 return static_cast<double>(std::get<uint8_t>(value));
288 case INT8:
289 return static_cast<double>(std::get<int8_t>(value));
290 case UINT16:
291 return static_cast<double>(std::get<uint16_t>(value));
292 case INT16:
293 return static_cast<double>(std::get<int16_t>(value));
294 case UINT32:
295 return static_cast<double>(std::get<uint32_t>(value));
296 case INT32:
297 return static_cast<double>(std::get<int32_t>(value));
298 default:
299 throw std::runtime_error(
300 fmt::format(FMT_COMPILE("Data type : '{}' cannot be casted to double."), to_string()));
301 }
302 }
303
304 HandleDataType from_string(const std::string & data_type) { return HandleDataType(data_type); }
305
306private:
307 Value value_ = UNKNOWN;
308};
309
315{
316 InterfaceDescription(const std::string & prefix_name_in, const InterfaceInfo & interface_info_in)
317 : prefix_name(prefix_name_in),
318 interface_info(interface_info_in),
320 {
321 }
322
326 std::string prefix_name;
327
332
336 std::string interface_name;
337
338 const std::string & get_prefix_name() const { return prefix_name; }
339
340 const std::string & get_interface_name() const { return interface_info.name; }
341
342 const std::string & get_name() const { return interface_name; }
343
344 const std::string & get_data_type_string() const { return interface_info.data_type; }
345
346 HandleDataType get_data_type() const { return HandleDataType(interface_info.data_type); }
347};
348
350{
354 std::string scheduling_policy = "synchronized";
356 std::vector<int> cpu_affinity_cores = {};
358 bool print_warnings = true;
359};
360
362#ifdef _MSC_VER
363#pragma warning(push)
364#pragma warning(disable : 4996)
365#else
366#pragma GCC diagnostic push
367#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
368#endif
370{
372 std::string name;
374 std::string type;
376 std::string group;
378 unsigned int rw_rate;
382 [[deprecated("Use async_params instead.")]] int thread_priority;
388 std::unordered_map<std::string, std::string> hardware_parameters;
393 std::vector<ComponentInfo> joints;
397 std::vector<MimicJoint> mimic_joints;
402 std::vector<ComponentInfo> sensors;
407 std::vector<ComponentInfo> gpios;
412 std::vector<TransmissionInfo> transmissions;
416 std::string original_xml;
420 std::unordered_map<std::string, joint_limits::JointLimits> limits;
421
427 std::unordered_map<std::string, joint_limits::SoftJointLimits> soft_limits;
428};
429#ifdef _MSC_VER
430#pragma warning(pop)
431#else
432#pragma GCC diagnostic pop
433#endif
434
435} // namespace hardware_interface
436#endif // HARDWARE_INTERFACE__HARDWARE_INFO_HPP_
Definition hardware_info.hpp:146
bool is_castable_to_double() const
Check if the HandleDataType can be casted to double.
Definition hardware_info.hpp:250
double cast_to_double(const HANDLE_DATATYPE &value) const
Cast the given value to double.
Definition hardware_info.hpp:276
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:144
Contains semantic info about a given actuator loaded from URDF for a transmission.
Definition hardware_info.hpp:119
Definition hardware_info.hpp:80
bool enable_limits
Whether limits are enabled for this component (set at joint level with <limits enable="....
Definition hardware_info.hpp:90
std::vector< InterfaceInfo > command_interfaces
Definition hardware_info.hpp:96
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:103
std::vector< InterfaceInfo > state_interfaces
Definition hardware_info.hpp:101
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:350
bool print_warnings
Whether to print warnings when the async thread doesn't meet its deadline.
Definition hardware_info.hpp:358
std::string scheduling_policy
Scheduling policy for the async worker thread.
Definition hardware_info.hpp:354
int thread_priority
Thread priority for the async worker thread.
Definition hardware_info.hpp:352
std::vector< int > cpu_affinity_cores
CPU affinity cores for the async worker thread.
Definition hardware_info.hpp:356
This structure stores information about hardware defined in a robot's URDF.
Definition hardware_info.hpp:370
std::string type
Type of the hardware: actuator, sensor or system.
Definition hardware_info.hpp:374
int thread_priority
Async thread priority.
Definition hardware_info.hpp:382
std::vector< MimicJoint > mimic_joints
Definition hardware_info.hpp:397
std::string hardware_plugin_name
Name of the pluginlib plugin of the hardware that will be loaded.
Definition hardware_info.hpp:386
std::unordered_map< std::string, joint_limits::JointLimits > limits
Definition hardware_info.hpp:420
HardwareAsyncParams async_params
Async Parameters.
Definition hardware_info.hpp:384
std::unordered_map< std::string, std::string > hardware_parameters
(Optional) Key-value pairs for hardware parameters.
Definition hardware_info.hpp:388
std::string group
Hardware group to which the hardware belongs.
Definition hardware_info.hpp:376
bool is_async
Component is async.
Definition hardware_info.hpp:380
std::unordered_map< std::string, joint_limits::SoftJointLimits > soft_limits
Definition hardware_info.hpp:427
std::vector< ComponentInfo > gpios
Definition hardware_info.hpp:407
std::vector< ComponentInfo > joints
Definition hardware_info.hpp:393
std::string original_xml
Definition hardware_info.hpp:416
std::string name
Name of the hardware.
Definition hardware_info.hpp:372
std::vector< ComponentInfo > sensors
Definition hardware_info.hpp:402
std::vector< TransmissionInfo > transmissions
Definition hardware_info.hpp:412
unsigned int rw_rate
Component's read and write rates in Hz.
Definition hardware_info.hpp:378
Definition hardware_info.hpp:315
InterfaceInfo interface_info
Definition hardware_info.hpp:331
std::string interface_name
Definition hardware_info.hpp:336
std::string prefix_name
Definition hardware_info.hpp:326
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:53
bool enable_limits
(Optional) enable or disable the limits for the command interfaces
Definition hardware_info.hpp:55
Contains semantic info about a given joint loaded from URDF for a transmission.
Definition hardware_info.hpp:108
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:130
std::unordered_map< std::string, std::string > parameters
(Optional) Key-value pairs of custom parameters
Definition hardware_info.hpp:136