1#ifndef HARDWARE_INTERFACE_H
2#define HARDWARE_INTERFACE_H
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/math_utils.h>
13#include <quad_utils/ros_utils.h>
15#include <sensor_msgs/Imu.h>
16#include <sensor_msgs/JointState.h>
17#include <std_msgs/UInt8.h>
20#include <eigen3/Eigen/Eigen>
21#define MATH_PI 3.141592
54 virtual bool send(
const quad_msgs::LegCommandArray& leg_command_array_msg,
55 const Eigen::VectorXd& user_tx_data) = 0;
64 virtual bool recv(sensor_msgs::JointState& joint_state_msg,
65 sensor_msgs::Imu& imu_msg,
66 Eigen::VectorXd& user_rx_data) = 0;
Implements an abstract class for robot hardware interfaces.
Definition hardware_interface.h:28
HardwareInterface()
Constructor for HardwareInterface.
Definition hardware_interface.cpp:3
virtual void unloadInterface()=0
Unload the hardware interface.
virtual bool recv(sensor_msgs::JointState &joint_state_msg, sensor_msgs::Imu &imu_msg, Eigen::VectorXd &user_rx_data)=0
Recieve data from the robot.
virtual bool send(const quad_msgs::LegCommandArray &leg_command_array_msg, const Eigen::VectorXd &user_tx_data)=0
Send commands to the robot.
virtual void loadInterface(int argc, char **argv)=0
Load the hardware interface.