#include <RmpXboxConverter.h>
Public Member Functions | |
virtual int | GetAudioCommand (const sensor_msgs::Joy &rJoyMessage) |
virtual bool | GetBoost (const sensor_msgs::Joy &rJoyMessage) |
virtual bool | GetDeadman (const sensor_msgs::Joy &rJoyMessage) |
virtual double | GetRotationalVelocity (const sensor_msgs::Joy &rJoyMessage) |
virtual double | GetTranslationalVelocity (const sensor_msgs::Joy &rJoyMessage) |
XboxWirelessConverter () | |
virtual | ~XboxWirelessConverter () |
Private Member Functions | |
void | IsValid (const sensor_msgs::Joy &rJoyMessage) |
This class converts Xbox controller input to Rmp commands.
Definition at line 47 of file RmpXboxConverter.h.
Constructor
Definition at line 55 of file RmpXboxConverter.cpp.
XboxWirelessConverter::~XboxWirelessConverter | ( | ) | [virtual] |
Destructor
Definition at line 59 of file RmpXboxConverter.cpp.
int XboxWirelessConverter::GetAudioCommand | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [virtual] |
Get audio command
rJoyMessage | joystick message |
Implements JoystickConverter.
Definition at line 90 of file RmpXboxConverter.cpp.
bool XboxWirelessConverter::GetBoost | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [virtual] |
Get wether the boost button is pressed
rJoyMessage | joystick message |
Implements JoystickConverter.
Definition at line 83 of file RmpXboxConverter.cpp.
bool XboxWirelessConverter::GetDeadman | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [virtual] |
Get wether the deadman button is pressed
rJoyMessage | joystick message |
Implements JoystickConverter.
Definition at line 76 of file RmpXboxConverter.cpp.
double XboxWirelessConverter::GetRotationalVelocity | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [virtual] |
Get the rotational velocity reading
rJoyMessage | joystick message |
Implements JoystickConverter.
Definition at line 69 of file RmpXboxConverter.cpp.
double XboxWirelessConverter::GetTranslationalVelocity | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [virtual] |
Get the translational velocity reading
rJoyMessage | joystick message |
Implements JoystickConverter.
Definition at line 62 of file RmpXboxConverter.cpp.
void XboxWirelessConverter::IsValid | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [private] |
Wether the joystick message is valid throw an exception otherwise
std::logic_error | if rJoyMessage does not match the Xbox wireless joystick message specifications |
Definition at line 102 of file RmpXboxConverter.cpp.