ros2_control - rolling
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 <string>
19 #include <unordered_map>
20 #include <vector>
21 
22 #include "joint_limits/joint_limits.hpp"
23 
24 namespace hardware_interface
25 {
31 {
36  std::string name;
38  std::string min;
40  std::string max;
42  std::string initial_value;
44  std::string data_type;
46  int size;
49 };
50 
52 struct MimicJoint
53 {
54  std::size_t joint_index;
55  std::size_t mimicked_joint_index;
56  double multiplier = 1.0;
57  double offset = 0.0;
58 };
59 
61 enum class MimicAttribute
62 {
63  NOT_SET,
64  TRUE,
65  FALSE
66 };
67 
73 {
75  std::string name;
77  std::string type;
78 
80  MimicAttribute is_mimic = MimicAttribute::NOT_SET;
81 
86  std::vector<InterfaceInfo> command_interfaces;
91  std::vector<InterfaceInfo> state_interfaces;
93  std::unordered_map<std::string, std::string> parameters;
94 };
95 
97 struct JointInfo
98 {
99  std::string name;
100  std::vector<std::string> state_interfaces;
101  std::vector<std::string> command_interfaces;
102  std::string role;
103  double mechanical_reduction = 1.0;
104  double offset = 0.0;
105 };
106 
109 {
110  std::string name;
111  std::vector<std::string> state_interfaces;
112  std::vector<std::string> command_interfaces;
113  std::string role;
114  double mechanical_reduction = 1.0;
115  double offset = 0.0;
116 };
117 
120 {
121  std::string name;
122  std::string type;
123  std::vector<JointInfo> joints;
124  std::vector<ActuatorInfo> actuators;
126  std::unordered_map<std::string, std::string> parameters;
127 };
128 
131 {
133  std::string name;
135  std::string type;
137  std::string group;
139  bool is_async;
141  std::string hardware_plugin_name;
143  std::unordered_map<std::string, std::string> hardware_parameters;
148  std::vector<ComponentInfo> joints;
152  std::vector<MimicJoint> mimic_joints;
157  std::vector<ComponentInfo> sensors;
162  std::vector<ComponentInfo> gpios;
167  std::vector<TransmissionInfo> transmissions;
171  std::string original_xml;
175  std::unordered_map<std::string, joint_limits::JointLimits> limits;
176 
182  std::unordered_map<std::string, joint_limits::SoftJointLimits> soft_limits;
183 };
184 
185 } // namespace hardware_interface
186 #endif // HARDWARE_INTERFACE__HARDWARE_INFO_HPP_
Definition: actuator.hpp:34
MimicAttribute
This enum is used to store the mimic attribute of a joint.
Definition: hardware_info.hpp:62
Contains semantic info about a given actuator loaded from URDF for a transmission.
Definition: hardware_info.hpp:109
Definition: hardware_info.hpp:73
std::vector< InterfaceInfo > command_interfaces
Definition: hardware_info.hpp:86
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:93
std::vector< InterfaceInfo > state_interfaces
Definition: hardware_info.hpp:91
std::string name
Name of the component.
Definition: hardware_info.hpp:75
MimicAttribute is_mimic
Hold the value of the mimic attribute if given, NOT_SET otherwise.
Definition: hardware_info.hpp:80
std::string type
Type of the component: sensor, joint, or GPIO.
Definition: hardware_info.hpp:77
This structure stores information about hardware defined in a robot's URDF.
Definition: hardware_info.hpp:131
std::string type
Type of the hardware: actuator, sensor or system.
Definition: hardware_info.hpp:135
std::vector< MimicJoint > mimic_joints
Definition: hardware_info.hpp:152
std::string hardware_plugin_name
Name of the pluginlib plugin of the hardware that will be loaded.
Definition: hardware_info.hpp:141
std::unordered_map< std::string, joint_limits::JointLimits > limits
Definition: hardware_info.hpp:175
std::unordered_map< std::string, std::string > hardware_parameters
(Optional) Key-value pairs for hardware parameters.
Definition: hardware_info.hpp:143
std::string group
Hardware group to which the hardware belongs.
Definition: hardware_info.hpp:137
bool is_async
Component is async.
Definition: hardware_info.hpp:139
std::unordered_map< std::string, joint_limits::SoftJointLimits > soft_limits
Definition: hardware_info.hpp:182
std::vector< ComponentInfo > gpios
Definition: hardware_info.hpp:162
std::vector< ComponentInfo > joints
Definition: hardware_info.hpp:148
std::string original_xml
Definition: hardware_info.hpp:171
std::string name
Name of the hardware.
Definition: hardware_info.hpp:133
std::vector< ComponentInfo > sensors
Definition: hardware_info.hpp:157
std::vector< TransmissionInfo > transmissions
Definition: hardware_info.hpp:167
Definition: hardware_info.hpp:31
std::string max
(Optional) Maximal allowed values of the interface.
Definition: hardware_info.hpp:40
std::string initial_value
(Optional) Initial value of the interface.
Definition: hardware_info.hpp:42
std::string name
Definition: hardware_info.hpp:36
int size
(Optional) If the handle is an array, the size of the array. Used by GPIOs.
Definition: hardware_info.hpp:46
std::string min
(Optional) Minimal allowed values of the interface.
Definition: hardware_info.hpp:38
std::string data_type
(Optional) The datatype of the interface, e.g. "bool", "int". Used by GPIOs.
Definition: hardware_info.hpp:44
bool enable_limits
(Optional) enable or disable the limits for the command interfaces
Definition: hardware_info.hpp:48
Contains semantic info about a given joint loaded from URDF for a transmission.
Definition: hardware_info.hpp:98
This structure stores information about a joint that is mimicking another joint.
Definition: hardware_info.hpp:53
Contains semantic info about a given transmission loaded from URDF.
Definition: hardware_info.hpp:120
std::unordered_map< std::string, std::string > parameters
(Optional) Key-value pairs of custom parameters
Definition: hardware_info.hpp:126