Quad-SDK
|
Hardware interface for the Spirit40 quadruped from Ghost Robotics. More...
#include <spirit_interface.h>
Public Member Functions | |
SpiritInterface () | |
Constructor for SpiritInterface. | |
virtual void | loadInterface (int argc, char **argv) |
Load the hardware interface. | |
virtual void | unloadInterface () |
Unload the hardware interface. | |
virtual bool | send (const quad_msgs::LegCommandArray &leg_command_array_msg, const Eigen::VectorXd &user_tx_data) |
Send commands to the robot via the mblink protocol. | |
virtual bool | recv (sensor_msgs::JointState &joint_state_msg, sensor_msgs::Imu &imu_msg, Eigen::VectorXd &user_rx_data) |
Recieve data from the robot via the mblink protocol. | |
![]() | |
HardwareInterface () | |
Constructor for HardwareInterface. | |
Public Attributes | |
MBLink | mblink_ |
Pointer to MBLink object. | |
MBData_t | mbdata_ |
Mainboard data. | |
std::vector< std::string > | joint_names_ |
Vector of joint names. | |
std::vector< int > | joint_indices_ = {8, 0, 1, 9, 2, 3, 10, 4, 5, 11, 6, 7} |
Vector denoting joint indices. | |
std::vector< double > | kt_vec_ |
Vector of kt values for each joint. | |
Hardware interface for the Spirit40 quadruped from Ghost Robotics.
SpiritInterface listens for joint control messages and outputs low level commands to the mainboard over mblink.
SpiritInterface::SpiritInterface | ( | ) |
Constructor for SpiritInterface.
|
virtual |
Load the hardware interface.
[in] | argc | Argument count |
[in] | argv | Argument vector |
Ghost MBLink interface class
Implements HardwareInterface.
|
virtual |
Recieve data from the robot via the mblink protocol.
[out] | joint_state_msg | Message containing joint state information |
[out] | imu_msg | Message containing imu information |
[out] | user_data | Vector containing user data |
Implements HardwareInterface.
|
virtual |
Send commands to the robot via the mblink protocol.
[in] | leg_command_array_msg | Message containing leg commands |
[in] | user_data | Vector containing user data |
Implements HardwareInterface.
|
virtual |
Unload the hardware interface.
Implements HardwareInterface.
std::vector<std::string> SpiritInterface::joint_names_ |
Vector of joint names.
std::vector<double> SpiritInterface::kt_vec_ |
Vector of kt values for each joint.