lmc_driver_node.cpp
Go to the documentation of this file.
1 #include <iostream>
2 
3 #include "ros/ros.h"
4 #include "leap_motion/Human.h"
5 
6 #include "../inc/lmc_listener.h"
7 #include "Leap.h"
8 
9 using namespace Leap;
10 
11 int main(int argc, char** argv) {
12 
13  ros::init(argc, argv, "leap_motion");
14  ros::NodeHandle nh("leap_motion");
15 
16  bool setup_params[7];
17 
18  // Read parameters from the defined in listener_params.yaml
19  nh.getParam("/enable_controller_info", setup_params[0] );
20  nh.getParam("/enable_frame_info", setup_params[1] );
21  nh.getParam("/enable_hand_info", setup_params[2] );
22 
23  nh.getParam("/enable_gesture_circle", setup_params[3] );
24  nh.getParam("/enable_gesture_swipe", setup_params[4] );
25  nh.getParam("/enable_gesture_screen_tap", setup_params[5] );
26  nh.getParam("/enable_gesture_key_tap", setup_params[6] );
27 
28  LeapListener listener(setup_params);
29  // Add a publisher to the leapListener object
30  listener.ros_publisher = nh.advertise<leap_motion::Human>("leap_device", 1);
31 
32  Controller controller;
33  controller.addListener(listener);
34  // Keep doing ROS spin until shutdown() or Ctrl+C
35  ros::spin();
36  controller.removeListener(listener);
37 
38  return 0;
39 }
LEAP_EXPORT bool addListener(Listener &listener)
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
def listener()
Definition: subscriber.py:23
ROSCPP_DECL void spin(Spinner &spinner)
Definition: Leap.h:48
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool getParam(const std::string &key, std::string &s) const
ros::Publisher ros_publisher
Definition: lmc_listener.h:26


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