Public Member Functions | Public Attributes | List of all members
HandsListener Class Reference
Inheritance diagram for HandsListener:
Inheritance graph
[legend]

Public Member Functions

virtual void onConnect (const Controller &)
 
virtual void onDeviceChange (const Controller &)
 
virtual void onDisconnect (const Controller &)
 
virtual void onExit (const Controller &)
 
virtual void onFocusGained (const Controller &)
 
virtual void onFocusLost (const Controller &)
 
virtual void onFrame (const Controller &)
 
virtual void onInit (const Controller &)
 
virtual void onServiceConnect (const Controller &)
 
virtual void onServiceDisconnect (const Controller &)
 
- 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 onImages (const Controller &)
 
virtual LEAP_EXPORT ~Listener ()
 

Public Attributes

ros::NodeHandle _node
 
ros::Publisher _pub_bone_only
 
ros::Publisher _pub_marker_array
 
unsigned int seq
 
- Public Attributes inherited from Leap::Listener
 this
 

Detailed Description

Definition at line 17 of file leap_hands.cpp.

Member Function Documentation

void HandsListener::onConnect ( const Controller )
virtual

Called when the Controller object connects to the Leap Motion software and the Leap Motion hardware device is plugged in, or when this Listener object is added to a Controller that is already connected.

When this callback is invoked, Controller::isServiceConnected is true, Controller::devices() is not empty, and, for at least one of the Device objects in the list, Device::isStreaming() is true.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.0

Reimplemented from Leap::Listener.

Definition at line 43 of file leap_hands.cpp.

void HandsListener::onDeviceChange ( const Controller )
virtual

Called when a Leap Motion controller plugged in, unplugged, or the device changes state.

State changes include changes in frame rate and entering or leaving "robust" mode. Note that there is currently no way to query whether a device is in robust mode. You can use Frame::currentFramerate() to get the framerate.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.2

Reimplemented from Leap::Listener.

Definition at line 126 of file leap_hands.cpp.

void HandsListener::onDisconnect ( const Controller )
virtual

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.

Note: When you launch a Leap-enabled application in a debugger, the Leap Motion library does not disconnect from the application. This is to allow you to step through code without losing the connection because of time outs.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.0

Reimplemented from Leap::Listener.

Definition at line 51 of file leap_hands.cpp.

void HandsListener::onExit ( const Controller )
virtual

Called when this Listener object is removed from the Controller or the Controller instance is destroyed.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.0

Reimplemented from Leap::Listener.

Definition at line 56 of file leap_hands.cpp.

void HandsListener::onFocusGained ( const Controller )
virtual

Called when this application becomes the foreground application.

Only the foreground application receives tracking data from the Leap Motion Controller. This function is only called when the controller object is in a connected state.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.0

Reimplemented from Leap::Listener.

Definition at line 118 of file leap_hands.cpp.

void HandsListener::onFocusLost ( const Controller )
virtual

Called when this application loses the foreground focus.

Only the foreground application receives tracking data from the Leap Motion Controller. This function is only called when the controller object is in a connected state.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.0

Reimplemented from Leap::Listener.

Definition at line 122 of file leap_hands.cpp.

void HandsListener::onFrame ( const Controller )
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 your onFrame handler executes. If your 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.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.0

Reimplemented from Leap::Listener.

Definition at line 60 of file leap_hands.cpp.

void HandsListener::onInit ( const Controller )
virtual

Called once, when this Listener object is newly added to a Controller.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.0

Reimplemented from Leap::Listener.

Definition at line 36 of file leap_hands.cpp.

void HandsListener::onServiceConnect ( const Controller )
virtual

Called when the Leap Motion daemon/service connects to your application Controller.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.2

Reimplemented from Leap::Listener.

Definition at line 136 of file leap_hands.cpp.

void HandsListener::onServiceDisconnect ( const Controller )
virtual

Called if the Leap Motion daemon/service disconnects from your application Controller.

Normally, this callback is not invoked. It is only called if some external event or problem shuts down the service or otherwise interrupts the connection.

Parameters
controllerThe Controller object invoking this callback function.
Since
1.2

Reimplemented from Leap::Listener.

Definition at line 140 of file leap_hands.cpp.

Member Data Documentation

ros::NodeHandle HandsListener::_node

Definition at line 19 of file leap_hands.cpp.

ros::Publisher HandsListener::_pub_bone_only

Definition at line 21 of file leap_hands.cpp.

ros::Publisher HandsListener::_pub_marker_array

Definition at line 20 of file leap_hands.cpp.

unsigned int HandsListener::seq

Definition at line 22 of file leap_hands.cpp.


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


leap_motion
Author(s): Florian Lier , Mirza Shah , Isaac IY Saito
autogenerated on Tue Jun 2 2020 03:58:01