Quad-SDK
Loading...
Searching...
No Matches
Public Member Functions | List of all members
HardwareInterface Class Referenceabstract

Implements an abstract class for robot hardware interfaces. More...

#include <hardware_interface.h>

Inheritance diagram for HardwareInterface:
Inheritance graph
[legend]

Public Member Functions

 HardwareInterface ()
 Constructor for HardwareInterface.
 
virtual void loadInterface (int argc, char **argv)=0
 Load the hardware interface.
 
virtual void unloadInterface ()=0
 Unload the hardware interface.
 
virtual bool send (const quad_msgs::LegCommandArray &leg_command_array_msg, const Eigen::VectorXd &user_tx_data)=0
 Send commands to the robot.
 
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.
 

Detailed Description

Implements an abstract class for robot hardware interfaces.

HardwareInterface provides an abstract robot hardware interface class. The virtual functions declared here must be implemented by the derived class.

Constructor & Destructor Documentation

◆ HardwareInterface()

HardwareInterface::HardwareInterface ( )

Constructor for HardwareInterface.

Returns
Constructed object of type HardwareInterface

Member Function Documentation

◆ loadInterface()

virtual void HardwareInterface::loadInterface ( int  argc,
char **  argv 
)
pure virtual

Load the hardware interface.

Parameters
[in]argcArgument count
[in]argvArgument vector

Implemented in SpiritInterface.

◆ recv()

virtual bool HardwareInterface::recv ( sensor_msgs::JointState &  joint_state_msg,
sensor_msgs::Imu &  imu_msg,
Eigen::VectorXd &  user_rx_data 
)
pure virtual

Recieve data from the robot.

Parameters
[out]joint_state_msgMessage containing joint state information
[out]imu_msgMessage containing imu information
[out]user_dataVector containing user data
Returns
Boolean for whether data was successfully received

Implemented in SpiritInterface.

◆ send()

virtual bool HardwareInterface::send ( const quad_msgs::LegCommandArray &  leg_command_array_msg,
const Eigen::VectorXd &  user_tx_data 
)
pure virtual

Send commands to the robot.

Parameters
[in]leg_command_array_msgMessage containing leg commands
[in]user_dataVector containing user data
Returns
boolean indicating success of transmission

Implemented in SpiritInterface.

◆ unloadInterface()

virtual void HardwareInterface::unloadInterface ( )
pure virtual

Unload the hardware interface.

Implemented in SpiritInterface.


The documentation for this class was generated from the following files: