#include <RmpJoystickConverter.h>

Public Types | |
| enum | JoystickType { XBOX_WIRELLESS } |
| typedef std::shared_ptr < JoystickConverter > | Ptr |
Public Member Functions | |
| virtual int | GetAudioCommand (const sensor_msgs::Joy &rJoyMessage)=0 |
| virtual bool | GetBoost (const sensor_msgs::Joy &rJoyMessage)=0 |
| virtual bool | GetDeadman (const sensor_msgs::Joy &rJoyMessage)=0 |
| virtual double | GetRotationalVelocity (const sensor_msgs::Joy &rJoyMessage)=0 |
| virtual double | GetTranslationalVelocity (const sensor_msgs::Joy &rJoyMessage)=0 |
| virtual | ~JoystickConverter () |
Static Public Member Functions | |
| static Ptr | Create (JoystickType joystickType) |
This class is an abstract base class. It converts joystick messages to Rmp commands.
Definition at line 50 of file RmpJoystickConverter.h.
| typedef std::shared_ptr<JoystickConverter> JoystickConverter::Ptr |
Definition at line 53 of file RmpJoystickConverter.h.
Define Joystick Type(s)
Definition at line 58 of file RmpJoystickConverter.h.
| virtual JoystickConverter::~JoystickConverter | ( | ) | [inline, virtual] |
Destructor
Definition at line 71 of file RmpJoystickConverter.h.
| JoystickConverter::Ptr JoystickConverter::Create | ( | JoystickType | joystickType | ) | [static] |
Create a joystick converter
Definition at line 44 of file RmpJoystickConverter.cpp.
| virtual int JoystickConverter::GetAudioCommand | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [pure virtual] |
Get audio command
| rJoyMessage | joystick message |
Implemented in XboxWirelessConverter.
| virtual bool JoystickConverter::GetBoost | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [pure virtual] |
Get wether the boost button is pressed
| rJoyMessage | joystick message |
Implemented in XboxWirelessConverter.
| virtual bool JoystickConverter::GetDeadman | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [pure virtual] |
Get wether the deadman button is pressed
| rJoyMessage | joystick message |
Implemented in XboxWirelessConverter.
| virtual double JoystickConverter::GetRotationalVelocity | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [pure virtual] |
Get the rotational velocity reading
| rJoyMessage | joystick message |
Implemented in XboxWirelessConverter.
| virtual double JoystickConverter::GetTranslationalVelocity | ( | const sensor_msgs::Joy & | rJoyMessage | ) | [pure virtual] |
Get the translational velocity reading
| rJoyMessage | joystick message |
Implemented in XboxWirelessConverter.