#include <lmc_listener.h>
Public Member Functions | |
LeapListener () | |
Uses default values for initial setup. More... | |
LeapListener (bool args[7]) | |
Uses the parameter server for initial setup values. More... | |
virtual void | onConnect (const Controller &) |
Called when a connection is established with the controller. More... | |
virtual void | onDisconnect (const Controller &) |
Called when the Controller object disconnects. More... | |
virtual void | onExit (const Controller &) |
Called when this Listener object is removed from the Controller. More... | |
virtual void | onFrame (const Controller &) |
Called when a new frame of hand and finger tracking data is available. More... | |
virtual void | onInit (const Controller &) |
Called once, when this Listener object is newly added to a Controller. More... | |
Public Member Functions inherited from Leap::Listener | |
def | __disown__ (self) |
def | __init__ (self) |
LEAP_EXPORT | Listener () |
def | on_connect (self, arg0) |
def | on_device_change (self, arg0) |
def | on_disconnect (self, arg0) |
def | on_exit (self, arg0) |
def | on_focus_gained (self, arg0) |
def | on_focus_lost (self, arg0) |
def | on_frame (self, arg0) |
def | on_images (self, arg0) |
def | on_init (self, arg0) |
def | on_service_connect (self, arg0) |
def | on_service_disconnect (self, arg0) |
virtual LEAP_EXPORT void | onDeviceChange (const Controller &) |
virtual LEAP_EXPORT void | onFocusGained (const Controller &) |
virtual LEAP_EXPORT void | onFocusLost (const Controller &) |
virtual LEAP_EXPORT void | onImages (const Controller &) |
virtual LEAP_EXPORT void | onServiceConnect (const Controller &) |
virtual LEAP_EXPORT void | onServiceDisconnect (const Controller &) |
virtual LEAP_EXPORT | ~Listener () |
Public Attributes | |
bool | enable_controller_info_ |
bool | enable_frame_info_ |
bool | enable_gesture_circle_ |
bool | enable_gesture_key_tap_ |
bool | enable_gesture_screen_tap_ |
bool | enable_gesture_swipe_ |
bool | enable_hand_info_ |
std::string | header_frame_id_ |
ros::Publisher | ros_publisher |
Public Attributes inherited from Leap::Listener | |
this | |
Definition at line 15 of file lmc_listener.h.
LeapListener::LeapListener | ( | ) |
Uses default values for initial setup.
Called when a LeapListener object is created with this constructor. Every gesture and ROS_INFO settings have been disabled.
Definition at line 28 of file lmc_listener.cpp.
LeapListener::LeapListener | ( | bool | args[7] | ) |
Uses the parameter server for initial setup values.
Called when a LeapListener object is created with this constructor.
frame_id | The value that is set as the ros_human_msg.header.frame_id. |
args[7] | Values that control info printing and gesture enabling. |
Definition at line 49 of file lmc_listener.cpp.
|
virtual |
Called when a connection is established with the controller.
Called when a connection is established between the controller and the Leap Motion software, the controller calls the Listener::onConnect() function.
controller | The Controller object invoking this callback function. |
Reimplemented from Leap::Listener.
Definition at line 70 of file lmc_listener.cpp.
|
virtual |
Called when the Controller object disconnects.
Called when the Controller object disconnects from the Leap Motion software or the Leap Motion hardware is unplugged.
The controller can disconnect when the Leap Motion device is unplugged, the user shuts the Leap Motion software down, or the Leap Motion software encounters an unrecoverable error.
controller | The Controller object invoking this callback function. |
Reimplemented from Leap::Listener.
Definition at line 151 of file lmc_listener.cpp.
|
virtual |
Called when this Listener object is removed from the Controller.
Called when this Listener object is removed from the Controller or the Controller instance is destroyed.
controller | The Controller object invoking this callback function. |
Reimplemented from Leap::Listener.
Definition at line 167 of file lmc_listener.cpp.
|
virtual |
Called when a new frame of hand and finger tracking data is available.
Access the new frame data using the Controller::frame() function.
Note, the Controller skips any pending onFrame events while the onFrame handler executes. If the implementation takes too long to return, one or more frames can be skipped. The Controller still inserts the skipped frames into the frame history. You can access recent frames by setting the history parameter when calling the Controller::frame() function. You can determine if any pending onFrame events were skipped by comparing the ID of the most recent frame with the ID of the last received frame.
controller | The Controller object invoking this callback function. |
Reimplemented from Leap::Listener.
Definition at line 189 of file lmc_listener.cpp.
|
virtual |
Called once, when this Listener object is newly added to a Controller.
When an instance of a Listener subclass is added to a Controller object, it calls the Listener::onInit() function when the listener is ready for use.
controller | The Controller object invoking this callback function. |
Reimplemented from Leap::Listener.
Definition at line 131 of file lmc_listener.cpp.
bool LeapListener::enable_controller_info_ |
Definition at line 29 of file lmc_listener.h.
bool LeapListener::enable_frame_info_ |
Definition at line 30 of file lmc_listener.h.
bool LeapListener::enable_gesture_circle_ |
Definition at line 33 of file lmc_listener.h.
bool LeapListener::enable_gesture_key_tap_ |
Definition at line 36 of file lmc_listener.h.
bool LeapListener::enable_gesture_screen_tap_ |
Definition at line 35 of file lmc_listener.h.
bool LeapListener::enable_gesture_swipe_ |
Definition at line 34 of file lmc_listener.h.
bool LeapListener::enable_hand_info_ |
Definition at line 31 of file lmc_listener.h.
std::string LeapListener::header_frame_id_ |
Definition at line 27 of file lmc_listener.h.
ros::Publisher LeapListener::ros_publisher |
Definition at line 26 of file lmc_listener.h.