Quad-SDK
Loading...
Searching...
No Matches
robot_driver.h
1#ifndef ROBOT_DRIVER_H
2#define ROBOT_DRIVER_H
3
4#include <eigen_conversions/eigen_msg.h>
5#include <quad_msgs/GRFArray.h>
6#include <quad_msgs/LegCommand.h>
7#include <quad_msgs/LegCommandArray.h>
8#include <quad_msgs/MotorCommand.h>
9#include <quad_msgs/MultiFootPlanContinuous.h>
10#include <quad_msgs/RobotPlan.h>
11#include <quad_msgs/RobotState.h>
12#include <quad_utils/function_timer.h>
13#include <quad_utils/math_utils.h>
14#include <quad_utils/ros_utils.h>
15#include <ros/ros.h>
16#include <std_msgs/Bool.h>
17#include <std_msgs/UInt8.h>
18
19#include <cmath>
20#include <eigen3/Eigen/Eigen>
21
22#include "robot_driver/controllers/grf_pid_controller.h"
23#include "robot_driver/controllers/inverse_dynamics_controller.h"
24#include "robot_driver/controllers/joint_controller.h"
25#include "robot_driver/controllers/leg_controller.h"
26#include "robot_driver/estimators/comp_filter_estimator.h"
27#include "robot_driver/estimators/ekf_estimator.h"
28#include "robot_driver/estimators/state_estimator.h"
29#include "robot_driver/hardware_interfaces/hardware_interface.h"
30#include "robot_driver/hardware_interfaces/spirit_interface.h"
31#include "robot_driver/robot_driver_utils.h"
32
33#define MATH_PI 3.141592
34
37
44 public:
50 RobotDriver(ros::NodeHandle nh, int argc, char** argv);
51
55 void spin();
56
57 private:
61 void initLegController();
62
67
71 void initStateEstimator();
72
77 void controlModeCallback(const std_msgs::UInt8::ConstPtr& msg);
78
83 void localPlanCallback(const quad_msgs::RobotPlan::ConstPtr& msg);
84
89 void robotStateCallback(const quad_msgs::RobotState::ConstPtr& msg);
90
95 void mocapCallback(const geometry_msgs::PoseStamped::ConstPtr& msg);
96
101 void trajectoryStateCallback(const quad_msgs::RobotState::ConstPtr& msg);
102
107 void singleJointCommandCallback(const geometry_msgs::Vector3::ConstPtr& msg);
108
112 void controlRestartFlagCallback(const std_msgs::Bool::ConstPtr& msg);
113
118 void remoteHeartbeatCallback(const std_msgs::Header::ConstPtr& msg);
119
124
128 bool updateState();
129
133 bool updateControl();
134
138 void publishState();
139
145 void publishControl(bool is_valid);
146
150 void publishHeartbeat();
151
153 ros::Subscriber control_mode_sub_;
154
156 ros::Subscriber body_plan_sub_;
157
159 ros::Subscriber local_plan_sub_;
160
162 ros::Subscriber mocap_sub_;
163
165 ros::Subscriber robot_state_sub_;
166
169
171 ros::Publisher robot_state_pub_;
172
173 // ROS publisher for state estimate
174 ros::Publisher trajectry_robot_state_pub_;
175
177 ros::Subscriber remote_heartbeat_sub_;
178
180 ros::Subscriber single_joint_cmd_sub_;
181
183 ros::Publisher robot_heartbeat_pub_;
184
187
189 ros::Publisher grf_pub_;
190
192 ros::Publisher imu_pub_;
193
195 ros::Publisher joint_state_pub_;
196
198 ros::NodeHandle nh_;
199
202
204 std::string controller_id_;
205
207 std::string estimator_id_;
208
211
214
216 const int num_feet_ = 4;
217
220
222 std::vector<double> torque_limits_;
223
225 const int SIT = 0;
226
228 const int READY = 1;
229
231 const int SIT_TO_READY = 2;
232
234 const int READY_TO_SIT = 3;
235
237 const int SAFETY = 4;
238
240 const int NONE = 0;
241
243 const int LOCAL_PLAN = 1;
244
246 const int GRFS = 2;
247
249 quad_msgs::RobotPlan::ConstPtr last_local_plan_msg_;
250
252 quad_msgs::RobotState last_robot_state_msg_;
253
255 quad_msgs::GRFArray::ConstPtr last_grf_array_msg_;
256
258 std_msgs::Header::ConstPtr last_remote_heartbeat_msg_;
259
262
263 // State timeout threshold in seconds
264 double last_state_time_;
265
266 // Remote heartbeat timeout threshold in seconds
267 double remote_heartbeat_received_time_;
268
270 const double transition_duration_ = 1.0;
271
274
277
280
283
286
288 quad_msgs::LegCommandArray leg_command_array_msg_;
289
291 quad_msgs::GRFArray grf_array_msg_;
292
294 Eigen::VectorXd user_tx_data_;
295
297 Eigen::VectorXd user_rx_data_;
298
301
303 std::vector<double> safety_kp_;
304 std::vector<double> safety_kd_;
305
307 std::vector<double> sit_kp_;
308 std::vector<double> sit_kd_;
309
311 std::vector<double> stand_kp_;
312 std::vector<double> stand_kd_;
313
315 std::vector<double> stance_kp_;
316 std::vector<double> stance_kd_;
317
319 std::vector<double> swing_kp_;
320 std::vector<double> swing_kd_;
321
323 std::vector<double> swing_kp_cart_;
324 std::vector<double> swing_kd_cart_;
325
327 std::vector<double> stand_joint_angles_;
328
330 std::vector<double> sit_joint_angles_;
331
333 std::shared_ptr<quad_utils::QuadKD> quadKD_;
334
336 std::shared_ptr<LegController> leg_controller_;
337
339 std::shared_ptr<StateEstimator> state_estimator_;
340
342 std::shared_ptr<HardwareInterface> hardware_interface_;
343
345 geometry_msgs::PoseStamped::ConstPtr last_mocap_msg_;
346
348 sensor_msgs::Imu last_imu_msg_;
349
351 sensor_msgs::JointState last_joint_state_msg_;
352
354 Eigen::Vector3d vel_estimate_;
355
357 Eigen::Vector3d mocap_vel_estimate_;
358
360 Eigen::Vector3d imu_vel_estimate_;
361
364
367
371
374
377
380
382 ros::Time t_pub_;
383
385 int argc_;
386
388 char** argv_;
389};
390
391#endif // ROBOT_DRIVER_H
Definition robot_driver.h:43
std::vector< double > stand_kp_
PD gain when in standing mode.
Definition robot_driver.h:311
ros::Time transition_timestamp_
Time at which to start transition.
Definition robot_driver.h:300
double heartbeat_timeout_
Timeout (in s) for receiving new heartbeat messages.
Definition robot_driver.h:279
bool updateState()
Update the most recent state message with the given data.
Definition robot_driver.cpp:310
ros::Time last_mocap_time_
Last mocap time.
Definition robot_driver.h:379
void checkMessagesForSafety()
Check to make sure required messages are fresh.
Definition robot_driver.cpp:284
const int READY
Define ids for control modes: Stand.
Definition robot_driver.h:228
void publishHeartbeat()
Function to publish heartbeat message.
Definition robot_driver.cpp:550
ros::Publisher joint_state_pub_
ROS publisher for joint data.
Definition robot_driver.h:195
ros::Subscriber single_joint_cmd_sub_
ROS subscriber for single joint command.
Definition robot_driver.h:180
const int READY_TO_SIT
Define ids for control modes: Stand to sit.
Definition robot_driver.h:234
void initStateEstimator()
Initializes state estimator object.
Definition robot_driver.cpp:148
std_msgs::Header last_robot_heartbeat_msg_
Most recent robot heartbeat.
Definition robot_driver.h:261
std::vector< double > sit_joint_angles_
Define sitting joint angles.
Definition robot_driver.h:330
Eigen::Vector3d vel_estimate_
Best estimate of velocity.
Definition robot_driver.h:354
void remoteHeartbeatCallback(const std_msgs::Header::ConstPtr &msg)
Callback to handle new remote heartbeat messages.
Definition robot_driver.cpp:273
void controlModeCallback(const std_msgs::UInt8::ConstPtr &msg)
Verifies and updates new control mode.
Definition robot_driver.cpp:197
void localPlanCallback(const quad_msgs::RobotPlan::ConstPtr &msg)
Callback function to handle new local plan (states and GRFs)
Definition robot_driver.cpp:228
quad_msgs::RobotState last_robot_state_msg_
Most recent state estimate.
Definition robot_driver.h:252
double mocap_rate_
Update rate of the motion capture system.
Definition robot_driver.h:373
double update_rate_
Update rate for computing new controls;.
Definition robot_driver.h:210
void initStateControlStructs()
Initializes states and controls structures.
Definition robot_driver.cpp:182
std::vector< double > swing_kp_
PD gain when foot is in swing.
Definition robot_driver.h:319
std::vector< double > stand_joint_angles_
Define standing joint angles.
Definition robot_driver.h:327
std::shared_ptr< StateEstimator > state_estimator_
State Estimator template class.
Definition robot_driver.h:339
bool updateControl()
Function to compute leg command array message.
Definition robot_driver.cpp:348
const int GRFS
Define ids for input types: grf array.
Definition robot_driver.h:246
const int LOCAL_PLAN
Define ids for input types: local plan.
Definition robot_driver.h:243
ros::Subscriber remote_heartbeat_sub_
ROS subscriber for remote heartbeat.
Definition robot_driver.h:177
void robotStateCallback(const quad_msgs::RobotState::ConstPtr &msg)
Callback function to handle current robot state.
Definition robot_driver.cpp:268
std::vector< double > sit_kp_
PD gain when in sit mode.
Definition robot_driver.h:307
double state_timeout_
Timeout (in s) for receiving new state messages.
Definition robot_driver.h:276
double remote_latency_threshold_error_
Latency threshold on robot messages for error (s)
Definition robot_driver.h:285
quad_msgs::LegCommandArray leg_command_array_msg_
Message for leg command array.
Definition robot_driver.h:288
const double transition_duration_
Duration for sit to stand behavior.
Definition robot_driver.h:270
const int NONE
Define ids for input types: none.
Definition robot_driver.h:240
Eigen::Vector3d mocap_vel_estimate_
Best estimate of velocity from mocap diff.
Definition robot_driver.h:357
std::vector< double > safety_kp_
PD gain when in safety mode.
Definition robot_driver.h:303
void publishState()
Publish the most recent state message with the given data.
Definition robot_driver.cpp:340
Eigen::VectorXd user_tx_data_
User transmission data.
Definition robot_driver.h:294
ros::Publisher imu_pub_
ROS publisher for imu data.
Definition robot_driver.h:192
sensor_msgs::JointState last_joint_state_msg_
Most recent joint data.
Definition robot_driver.h:351
std::string controller_id_
Controller type.
Definition robot_driver.h:204
double mocap_dropout_threshold_
Definition robot_driver.h:370
const int num_feet_
Number of feet.
Definition robot_driver.h:216
const int SAFETY
Define ids for control modes: Safety.
Definition robot_driver.h:237
std_msgs::Header::ConstPtr last_remote_heartbeat_msg_
Most recent remote heartbeat.
Definition robot_driver.h:258
ros::Subscriber control_mode_sub_
Subscriber for control mode.
Definition robot_driver.h:153
std::vector< double > stance_kp_
PD gain when foot is in stance.
Definition robot_driver.h:315
double remote_latency_threshold_warn_
Latency threshold on robot messages for warnings (s)
Definition robot_driver.h:282
void controlRestartFlagCallback(const std_msgs::Bool::ConstPtr &msg)
Callback to handle control restart flag messages.
Definition robot_driver.cpp:223
ros::Subscriber robot_state_sub_
ROS subscriber for state estimate.
Definition robot_driver.h:165
void spin()
Calls ros spinOnce and pubs data at set frequency.
Definition robot_driver.cpp:559
std::shared_ptr< quad_utils::QuadKD > quadKD_
QuadKD class.
Definition robot_driver.h:333
void publishControl(bool is_valid)
Function to publish leg command array message.
Definition robot_driver.cpp:530
sensor_msgs::Imu last_imu_msg_
Most recent IMU data.
Definition robot_driver.h:348
std::shared_ptr< HardwareInterface > hardware_interface_
Mblink converter object.
Definition robot_driver.h:342
std::vector< double > torque_limits_
Torque limits.
Definition robot_driver.h:222
const int SIT_TO_READY
Define ids for control modes: Sit to stand.
Definition robot_driver.h:231
std::shared_ptr< LegController > leg_controller_
Leg Controller template class.
Definition robot_driver.h:336
bool is_hardware_
Boolean for whether robot layer is hardware (else sim)
Definition robot_driver.h:201
std::string estimator_id_
Estimator type.
Definition robot_driver.h:207
double input_timeout_
Timeout (in s) for receiving new input reference messages.
Definition robot_driver.h:273
std::vector< double > swing_kp_cart_
PD gain when foot is in swing (Cartesian)
Definition robot_driver.h:323
void trajectoryStateCallback(const quad_msgs::RobotState::ConstPtr &msg)
Callback function to handle reference trajectory state.
ros::Time t_pub_
Time of last publishing.
Definition robot_driver.h:382
ros::Subscriber local_plan_sub_
ROS subscriber for local plan.
Definition robot_driver.h:159
ros::Publisher robot_heartbeat_pub_
ROS publisher for robot heartbeat.
Definition robot_driver.h:183
void singleJointCommandCallback(const geometry_msgs::Vector3::ConstPtr &msg)
Callback to handle new leg override commands.
Definition robot_driver.cpp:215
Eigen::VectorXd user_rx_data_
User recieved data.
Definition robot_driver.h:297
ros::Subscriber control_restart_flag_sub_
ROS subscriber for control restart flag.
Definition robot_driver.h:168
double publish_rate_
Update rate for publishing data to ROS;.
Definition robot_driver.h:213
quad_msgs::GRFArray grf_array_msg_
Message for leg command array.
Definition robot_driver.h:291
ros::Publisher grf_pub_
ROS publisher for desired GRF.
Definition robot_driver.h:189
Eigen::Vector3d imu_vel_estimate_
Best estimate of imu velocity.
Definition robot_driver.h:360
const int SIT
Define ids for control modes: Sit.
Definition robot_driver.h:225
double filter_weight_
Velocity filter weight.
Definition robot_driver.h:366
ros::NodeHandle nh_
Nodehandle to pub to and sub from.
Definition robot_driver.h:198
void mocapCallback(const geometry_msgs::PoseStamped::ConstPtr &msg)
Callback function to handle current robot pose.
Definition robot_driver.cpp:238
int control_mode_
Robot mode.
Definition robot_driver.h:219
ros::Publisher robot_state_pub_
ROS publisher for ground truth state.
Definition robot_driver.h:171
double filter_time_constant_
Velocity filter time constant.
Definition robot_driver.h:363
geometry_msgs::PoseStamped::ConstPtr last_mocap_msg_
Last mocap data.
Definition robot_driver.h:345
char ** argv_
Required for some hardware interfaces.
Definition robot_driver.h:388
ros::Subscriber body_plan_sub_
ROS subscriber for body plan.
Definition robot_driver.h:156
void initLegController()
Initializes leg controller object.
Definition robot_driver.cpp:164
int argc_
Required for some hardware interfaces.
Definition robot_driver.h:385
ros::Subscriber mocap_sub_
ROS subscriber for local plan.
Definition robot_driver.h:162
quad_msgs::RobotPlan::ConstPtr last_local_plan_msg_
Most recent local plan.
Definition robot_driver.h:249
double last_mainboard_time_
Last mainboard time.
Definition robot_driver.h:376
quad_msgs::GRFArray::ConstPtr last_grf_array_msg_
Most recent local plan.
Definition robot_driver.h:255
ros::Publisher leg_command_array_pub_
ROS publisher for inverse dynamics.
Definition robot_driver.h:186