Public Member Functions | Public Attributes
LeapListener Class Reference

#include <lmc_listener.h>

Inheritance diagram for LeapListener:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 LeapListener ()
 Uses default values for initial setup.
 LeapListener (bool args[7])
 Uses the parameter server for initial setup values.
virtual void onConnect (const Controller &)
 Called when a connection is established with the controller.
virtual void onDisconnect (const Controller &)
 Called when the Controller object disconnects.
virtual void onExit (const Controller &)
 Called when this Listener object is removed from the Controller.
virtual void onFrame (const Controller &)
 Called when a new frame of hand and finger tracking data is available.
virtual void onInit (const Controller &)
 Called once, when this Listener object is newly added to a Controller.

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

Detailed Description

Definition at line 15 of file lmc_listener.h.


Constructor & Destructor Documentation

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 26 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.

Parameters:
frame_idThe 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 47 of file lmc_listener.cpp.


Member Function Documentation

void LeapListener::onConnect ( const Controller controller) [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.

Parameters:
controllerThe Controller object invoking this callback function.

Reimplemented from Leap::Listener.

Definition at line 68 of file lmc_listener.cpp.

void LeapListener::onDisconnect ( const Controller controller) [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.

Parameters:
controllerThe Controller object invoking this callback function.

Reimplemented from Leap::Listener.

Definition at line 149 of file lmc_listener.cpp.

void LeapListener::onExit ( const Controller controller) [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.

Parameters:
controllerThe Controller object invoking this callback function.

Reimplemented from Leap::Listener.

Definition at line 165 of file lmc_listener.cpp.

void LeapListener::onFrame ( const Controller 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 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.

Parameters:
controllerThe Controller object invoking this callback function.

Reimplemented from Leap::Listener.

Definition at line 187 of file lmc_listener.cpp.

void LeapListener::onInit ( const Controller controller) [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.

Parameters:
controllerThe Controller object invoking this callback function.

Reimplemented from Leap::Listener.

Definition at line 129 of file lmc_listener.cpp.


Member Data Documentation

Definition at line 29 of file lmc_listener.h.

Definition at line 30 of file lmc_listener.h.

Definition at line 33 of file lmc_listener.h.

Definition at line 36 of file lmc_listener.h.

Definition at line 35 of file lmc_listener.h.

Definition at line 34 of file lmc_listener.h.

Definition at line 31 of file lmc_listener.h.

Definition at line 27 of file lmc_listener.h.

Definition at line 26 of file lmc_listener.h.


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


leap_motion
Author(s): Florian Lier , Mirza Shah , Isaac IY Saito
autogenerated on Sat Jun 8 2019 18:47:25