ros2_control - humble
Loading...
Searching...
No Matches
data.hpp
1
20#pragma once
21
22#include <Eigen/Core>
23#include <Eigen/Geometry>
24#include <hardware_interface/types/hardware_interface_type_values.hpp>
25#include "control_toolbox/pid_ros.hpp"
26
27#include <string>
28#include <vector>
29
31{
32
44enum class ActuatorType
45{
46 UNKNOWN,
47 MOTOR,
48 POSITION,
49 VELOCITY,
50 PASSIVE,
51 CUSTOM
52};
53
58{
59 explicit InterfaceData(const std::string& command_interface) : command_interface_(command_interface)
60 {
61 }
62
63 std::string command_interface_;
64 double command_ = std::numeric_limits<double>::quiet_NaN();
65 double state_ = std::numeric_limits<double>::quiet_NaN();
66
67 // this is the "sink" that will be part of the transmission Joint/Actuator handles
68 double transmission_passthrough_ = std::numeric_limits<double>::quiet_NaN();
69};
70
93{
94 std::string joint_name = "";
98 std::shared_ptr<control_toolbox::PidROS> pos_pid{ nullptr };
99 std::shared_ptr<control_toolbox::PidROS> vel_pid{ nullptr };
100 ActuatorType actuator_type{ ActuatorType::UNKNOWN };
101 int mj_joint_type = -1;
102 int mj_pos_adr = -1;
103 int mj_vel_adr = -1;
104 int mj_actuator_id = -1;
105
106 // Booleans record whether or not we should be writing commands to these interfaces
107 // based on if they have been claimed.
108 bool is_position_control_enabled{ false };
109 bool is_position_pid_control_enabled{ false };
110 bool is_velocity_pid_control_enabled{ false };
111 bool is_velocity_control_enabled{ false };
112 bool is_effort_control_enabled{ false };
113 bool has_pos_pid{ false };
114 bool has_vel_pid{ false };
115
116 void copy_state_to_transmission()
117 {
118 position_interface.transmission_passthrough_ = position_interface.state_;
119 velocity_interface.transmission_passthrough_ = velocity_interface.state_;
120 effort_interface.transmission_passthrough_ = effort_interface.state_;
121 }
122
123 void copy_command_from_transmission()
124 {
125 position_interface.command_ = position_interface.transmission_passthrough_;
126 velocity_interface.command_ = velocity_interface.transmission_passthrough_;
127 effort_interface.command_ = effort_interface.transmission_passthrough_;
128 }
129
130 void copy_command_to_state()
131 {
132 position_interface.state_ = position_interface.command_;
133 velocity_interface.state_ = velocity_interface.command_;
134 effort_interface.state_ = effort_interface.command_;
135 }
136};
137
153{
154 std::string name = "";
158
159 std::vector<std::string> command_interfaces = {};
160
161 bool is_mimic{ false };
162 long int mimicked_joint_index;
163 double mimic_multiplier;
164
165 bool is_position_control_enabled{ false };
166 bool is_velocity_control_enabled{ false };
167 bool is_effort_control_enabled{ false };
168
169 void copy_state_from_transmission()
170 {
171 position_interface.state_ = position_interface.transmission_passthrough_;
172 velocity_interface.state_ = velocity_interface.transmission_passthrough_;
173 effort_interface.state_ = effort_interface.transmission_passthrough_;
174 }
175
176 void copy_command_to_transmission()
177 {
178 position_interface.transmission_passthrough_ = position_interface.command_;
179 velocity_interface.transmission_passthrough_ = velocity_interface.command_;
180 effort_interface.transmission_passthrough_ = effort_interface.command_;
181 }
182
183 void copy_state_to_command()
184 {
185 position_interface.command_ = position_interface.state_;
186 velocity_interface.command_ = velocity_interface.state_;
187 effort_interface.command_ = effort_interface.state_;
188 }
189};
190
191template <typename T>
193{
194 std::string name;
195 T data;
196 int mj_sensor_index;
197};
198
200{
201 std::string name;
204};
205
207{
208 std::string name;
210 SensorData<Eigen::Vector3d> angular_velocity;
211 SensorData<Eigen::Vector3d> linear_acceleration;
212
213 // These are currently unused but added to support controllers that require them.
214 std::vector<double> orientation_covariance;
215 std::vector<double> angular_velocity_covariance;
216 std::vector<double> linear_acceleration_covariance;
217};
218
219} // namespace mujoco_ros2_control
constexpr char HW_IF_EFFORT[]
Constant defining effort interface.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition hardware_interface_type_values.hpp:21
Definition data.hpp:31
ActuatorType
Definition data.hpp:45
Definition data.hpp:200
Definition data.hpp:207
Definition data.hpp:193
Definition data.hpp:153