#include <joystick_handler.h>

Public Member Functions | |
| void | joyCallback (const sensor_msgs::Joy::ConstPtr &joy_msg) override |
| JoystickButton (int button, double thresh=1.0) | |
| JoystickButton (XmlRpc::XmlRpcValue ¶ms) | |
Public Member Functions inherited from vigir_footstep_planning::JoystickInputHandle | |
| virtual double | getValue () const |
| virtual bool | isPressed () const |
| JoystickInputHandle (double thresh=1.0) | |
Protected Attributes | |
| int | button_id_ |
Protected Attributes inherited from vigir_footstep_planning::JoystickInputHandle | |
| double | thresh_ |
| double | val_ |
Additional Inherited Members | |
Public Types inherited from vigir_footstep_planning::JoystickInputHandle | |
| typedef boost::shared_ptr< JoystickInputHandle > | ConstPtr |
| typedef boost::shared_ptr< JoystickInputHandle > | Ptr |
Definition at line 64 of file joystick_handler.h.
|
inline |
Definition at line 68 of file joystick_handler.h.
|
inline |
Definition at line 75 of file joystick_handler.h.
|
inlineoverridevirtual |
Implements vigir_footstep_planning::JoystickInputHandle.
Definition at line 79 of file joystick_handler.h.
|
protected |
Definition at line 88 of file joystick_handler.h.