Public Types | Public Member Functions | Static Public Member Functions
JoystickConverter Class Reference

#include <RmpJoystickConverter.h>

Inheritance diagram for JoystickConverter:
Inheritance graph
[legend]

List of all members.

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)

Detailed Description

This class is an abstract base class. It converts joystick messages to Rmp commands.

Definition at line 50 of file RmpJoystickConverter.h.


Member Typedef Documentation

typedef std::shared_ptr<JoystickConverter> JoystickConverter::Ptr

Definition at line 53 of file RmpJoystickConverter.h.


Member Enumeration Documentation

Define Joystick Type(s)

Enumerator:
XBOX_WIRELLESS 

Definition at line 58 of file RmpJoystickConverter.h.


Constructor & Destructor Documentation

virtual JoystickConverter::~JoystickConverter ( ) [inline, virtual]

Destructor

Definition at line 71 of file RmpJoystickConverter.h.


Member Function Documentation

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

Parameters:
rJoyMessagejoystick message
Returns:
return audio command or -1 if no command

Implemented in XboxWirelessConverter.

virtual bool JoystickConverter::GetBoost ( const sensor_msgs::Joy &  rJoyMessage) [pure virtual]

Get wether the boost button is pressed

Parameters:
rJoyMessagejoystick message
Returns:
wether the button is pressed

Implemented in XboxWirelessConverter.

virtual bool JoystickConverter::GetDeadman ( const sensor_msgs::Joy &  rJoyMessage) [pure virtual]

Get wether the deadman button is pressed

Parameters:
rJoyMessagejoystick message
Returns:
wether the button is pressed

Implemented in XboxWirelessConverter.

virtual double JoystickConverter::GetRotationalVelocity ( const sensor_msgs::Joy &  rJoyMessage) [pure virtual]

Get the rotational velocity reading

Parameters:
rJoyMessagejoystick message
Returns:
axe/button reading

Implemented in XboxWirelessConverter.

virtual double JoystickConverter::GetTranslationalVelocity ( const sensor_msgs::Joy &  rJoyMessage) [pure virtual]

Get the translational velocity reading

Parameters:
rJoyMessagejoystick message
Returns:
axe/button reading

Implemented in XboxWirelessConverter.


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


rmp_teleop
Author(s):
autogenerated on Wed Aug 26 2015 16:24:37