leap_hands.cpp
Go to the documentation of this file.
1 #include <iostream>
2 #include <string.h>
3 #include "Leap.h"
4 #include "ros/ros.h"
5 #include "visualization_msgs/MarkerArray.h"
6 #include "geometry_msgs/PoseStamped.h"
7 
8 #include <sstream>
9 
10 /* ##################################################
11  Deprecated and will be removed in the future
12 ################################################## */
13 
14 using namespace Leap;
15 using namespace std;
16 
17 class HandsListener : public Listener {
18  public:
22  unsigned int seq;
23  virtual void onInit(const Controller&);
24  virtual void onConnect(const Controller&);
25  virtual void onDisconnect(const Controller&);
26  virtual void onExit(const Controller&);
27  virtual void onFrame(const Controller&);
28  virtual void onFocusGained(const Controller&);
29  virtual void onFocusLost(const Controller&);
30  virtual void onDeviceChange(const Controller&);
31  virtual void onServiceConnect(const Controller&);
32  virtual void onServiceDisconnect(const Controller&);
33  private:
34 };
35 
36 void HandsListener::onInit(const Controller& controller) {
37  std::cout << "Initialized" << std::endl;
38  _pub_marker_array = _node.advertise<visualization_msgs::MarkerArray>("hands", 1);
39  _pub_bone_only = _node.advertise<visualization_msgs::Marker>("hands_line", 1);
40 }
41 
42 
43 void HandsListener::onConnect(const Controller& controller) {
44  std::cout << "Connected" << std::endl;
49 }
50 
51 void HandsListener::onDisconnect(const Controller& controller) {
52  // Note: not dispatched when running in a debugger.
53  std::cout << "Disconnected" << std::endl;
54 }
55 
56 void HandsListener::onExit(const Controller& controller) {
57  std::cout << "Exited" << std::endl;
58 }
59 
60 void HandsListener::onFrame(const Controller& controller) {
61  // Get the most recent frame and report some basic information
62  const Frame frame = controller.frame();
63  //ROS_INFO("flags = %i", (int) controller.policyFlags());
64  visualization_msgs::Marker marker_msg, joint_msg;
65  visualization_msgs::MarkerArray marker_array_msg;
66  marker_msg.header.frame_id=joint_msg.header.frame_id="/leap_optical_frame";
67  marker_msg.header.stamp=joint_msg.header.stamp=ros::Time::now();
68  marker_msg.ns="leap_marker";
69  joint_msg.ns="joint";
70  marker_msg.id = 0;
71  joint_msg.id = 0;
72  marker_msg.type = visualization_msgs::Marker::LINE_LIST;
73  joint_msg.type = visualization_msgs::Marker::SPHERE;
74  marker_msg.scale.x = 0.005;
75  joint_msg.scale.x = joint_msg.scale.y = joint_msg.scale.z = 0.015;
76  joint_msg.color.r = .0f;
77  joint_msg.color.g = 1.0f;
78  joint_msg.color.b = 1.0f;
79  joint_msg.color.a = 0.7f;
80  marker_msg.action = joint_msg.action = visualization_msgs::Marker::ADD;
81  marker_msg.lifetime = joint_msg.lifetime = ros::Duration(0.1);
82 
83  HandList hands = frame.hands();
84  for (HandList::const_iterator hl = hands.begin(); hl != hands.end(); ++hl) {
85  // Get the first hand
86  const Hand hand = *hl;
87  // Get the Arm bone
88  // Get fingers
89  const FingerList fingers = hand.fingers();
90  for (FingerList::const_iterator fl = fingers.begin(); fl != fingers.end(); ++fl) {
91  const Finger finger = *fl;
92  // Get finger bones
93  for (int b = 0; b < 4; ++b) {
94  Bone::Type boneType = static_cast<Bone::Type>(b);
95  Bone bone = finger.bone(boneType);
96  geometry_msgs::Point point;
97  point.x = -bone.prevJoint().x/1000;
98  point.y = bone.prevJoint().z/1000;
99  point.z = bone.prevJoint().y/1000;
100  marker_msg.points.push_back(point);
101  point.x = joint_msg.pose.position.x = -bone.nextJoint().x/1000;
102  point.y = joint_msg.pose.position.y = bone.nextJoint().z/1000;
103  point.z = joint_msg.pose.position.z = bone.nextJoint().y/1000;
104  marker_msg.points.push_back(point);
105  joint_msg.id = joint_msg.id+1;
106  marker_array_msg.markers.push_back(joint_msg);
107  std_msgs::ColorRGBA color;
108  color.r = 1.0f; color.g=.0f; color.b=.0f, color.a=1.0f;
109  marker_msg.colors.push_back(color);
110  marker_msg.colors.push_back(color);
111  }
112  }
113  }
114  _pub_marker_array.publish(marker_array_msg);
115  _pub_bone_only.publish(marker_msg);
116 }
117 
118 void HandsListener::onFocusGained(const Controller& controller) {
119  std::cout << "Focus Gained" << std::endl;
120 }
121 
122 void HandsListener::onFocusLost(const Controller& controller) {
123  std::cout << "Focus Lost" << std::endl;
124 }
125 
126 void HandsListener::onDeviceChange(const Controller& controller) {
127  std::cout << "Device Changed" << std::endl;
128  const DeviceList devices = controller.devices();
129 
130  for (int i = 0; i < devices.count(); ++i) {
131  std::cout << "id: " << devices[i].toString() << std::endl;
132  std::cout << " isStreaming: " << (devices[i].isStreaming() ? "true" : "false") << std::endl;
133  }
134 }
135 
137  std::cout << "Service Connected" << std::endl;
138 }
139 
141  std::cout << "Service Disconnected" << std::endl;
142 }
143 
144 int main(int argc, char** argv) {
145  ros::init(argc, argv, "leap_sender");
146  // Create a sample listener and controller
148  Controller controller;
149 
150  // Have the sample listener receive events from the controller
151  controller.addListener(listener);
152 
153  controller.setPolicyFlags(static_cast<Leap::Controller::PolicyFlag> (Leap::Controller::POLICY_IMAGES));
154  ros::spin();
155  // Remove the sample listener when done
156  controller.removeListener(listener);
157 
158  return 0;
159 }
ros::Publisher _pub_bone_only
Definition: leap_hands.cpp:21
LEAP_EXPORT void setPolicyFlags(PolicyFlag flags) const
LEAP_EXPORT void enableGesture(Gesture::Type type, bool enable=true) const
LEAP_EXPORT const_iterator begin() const
virtual void onServiceConnect(const Controller &)
Definition: leap_hands.cpp:136
LEAP_EXPORT bool addListener(Listener &listener)
virtual void onExit(const Controller &)
Definition: leap_hands.cpp:56
virtual void onFocusLost(const Controller &)
Definition: leap_hands.cpp:122
LEAP_EXPORT Vector prevJoint() const
LEAP_EXPORT const_iterator end() const
LEAP_EXPORT const_iterator begin() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
LEAP_EXPORT Vector nextJoint() const
virtual void onInit(const Controller &)
Definition: leap_hands.cpp:36
def listener()
Definition: subscriber.py:23
ROSCPP_DECL void spin(Spinner &spinner)
virtual void onServiceDisconnect(const Controller &)
Definition: leap_hands.cpp:140
Definition: Leap.h:48
ros::NodeHandle _node
Definition: leap_hands.cpp:19
LEAP_EXPORT Bone bone(Bone::Type boneIx) const
LEAP_EXPORT const_iterator end() const
std::vector< std::vector< lpf > > hands
ros::Publisher _pub_marker_array
Definition: leap_hands.cpp:20
virtual void onDeviceChange(const Controller &)
Definition: leap_hands.cpp:126
LEAP_EXPORT int count() const
virtual void onConnect(const Controller &)
Definition: leap_hands.cpp:43
int main(int argc, char **argv)
Definition: leap_hands.cpp:144
virtual void onDisconnect(const Controller &)
Definition: leap_hands.cpp:51
static Time now()
LEAP_EXPORT bool removeListener(Listener &listener)
LEAP_EXPORT Frame frame(int history=0) const
virtual void onFocusGained(const Controller &)
Definition: leap_hands.cpp:118
unsigned int seq
Definition: leap_hands.cpp:22
virtual void onFrame(const Controller &)
Definition: leap_hands.cpp:60


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