Quad-SDK
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
SpiritInterface Class Reference

Hardware interface for the Spirit40 quadruped from Ghost Robotics. More...

#include <spirit_interface.h>

Inheritance diagram for SpiritInterface:
Inheritance graph
[legend]
Collaboration diagram for SpiritInterface:
Collaboration graph
[legend]

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.
 
- Public Member Functions inherited from HardwareInterface
 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.
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ SpiritInterface()

SpiritInterface::SpiritInterface ( )

Constructor for SpiritInterface.

Returns
Constructed object of type SpiritInterface

Member Function Documentation

◆ loadInterface()

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

Load the hardware interface.

Parameters
[in]argcArgument count
[in]argvArgument vector

Ghost MBLink interface class

Implements HardwareInterface.

◆ recv()

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

Recieve data from the robot via the mblink protocol.

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

Implements HardwareInterface.

◆ send()

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

Send commands to the robot via the mblink protocol.

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

Implements HardwareInterface.

◆ unloadInterface()

void SpiritInterface::unloadInterface ( )
virtual

Unload the hardware interface.

Implements HardwareInterface.

Member Data Documentation

◆ joint_names_

std::vector<std::string> SpiritInterface::joint_names_
Initial value:
= {"8", "0", "1", "9", "2", "3",
"10", "4", "5", "11", "6", "7"}

Vector of joint names.

◆ kt_vec_

std::vector<double> SpiritInterface::kt_vec_
Initial value:
= {0.546, 0.546, 1.092, 0.546, 0.546, 1.092,
0.546, 0.546, 1.092, 0.546, 0.546, 1.092}

Vector of kt values for each joint.


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