00001 #include <iostream> 00002 #include <string.h> 00003 #include "Leap.h" 00004 #include "ros/ros.h" 00005 #include "visualization_msgs/MarkerArray.h" 00006 #include "geometry_msgs/PoseStamped.h" 00007 00008 #include <sstream> 00009 00010 /* ################################################## 00011 Deprecated and will be removed in the future 00012 ################################################## */ 00013 00014 using namespace Leap; 00015 using namespace std; 00016 00017 class HandsListener : public Listener { 00018 public: 00019 ros::NodeHandle _node; 00020 ros::Publisher _pub_marker_array; 00021 ros::Publisher _pub_bone_only; 00022 unsigned int seq; 00023 virtual void onInit(const Controller&); 00024 virtual void onConnect(const Controller&); 00025 virtual void onDisconnect(const Controller&); 00026 virtual void onExit(const Controller&); 00027 virtual void onFrame(const Controller&); 00028 virtual void onFocusGained(const Controller&); 00029 virtual void onFocusLost(const Controller&); 00030 virtual void onDeviceChange(const Controller&); 00031 virtual void onServiceConnect(const Controller&); 00032 virtual void onServiceDisconnect(const Controller&); 00033 private: 00034 }; 00035 00036 void HandsListener::onInit(const Controller& controller) { 00037 std::cout << "Initialized" << std::endl; 00038 _pub_marker_array = _node.advertise<visualization_msgs::MarkerArray>("hands", 1); 00039 _pub_bone_only = _node.advertise<visualization_msgs::Marker>("hands_line", 1); 00040 } 00041 00042 00043 void HandsListener::onConnect(const Controller& controller) { 00044 std::cout << "Connected" << std::endl; 00045 controller.enableGesture(Gesture::TYPE_CIRCLE); 00046 controller.enableGesture(Gesture::TYPE_KEY_TAP); 00047 controller.enableGesture(Gesture::TYPE_SCREEN_TAP); 00048 controller.enableGesture(Gesture::TYPE_SWIPE); 00049 } 00050 00051 void HandsListener::onDisconnect(const Controller& controller) { 00052 // Note: not dispatched when running in a debugger. 00053 std::cout << "Disconnected" << std::endl; 00054 } 00055 00056 void HandsListener::onExit(const Controller& controller) { 00057 std::cout << "Exited" << std::endl; 00058 } 00059 00060 void HandsListener::onFrame(const Controller& controller) { 00061 // Get the most recent frame and report some basic information 00062 const Frame frame = controller.frame(); 00063 //ROS_INFO("flags = %i", (int) controller.policyFlags()); 00064 visualization_msgs::Marker marker_msg, joint_msg; 00065 visualization_msgs::MarkerArray marker_array_msg; 00066 marker_msg.header.frame_id=joint_msg.header.frame_id="/leap_optical_frame"; 00067 marker_msg.header.stamp=joint_msg.header.stamp=ros::Time::now(); 00068 marker_msg.ns="leap_marker"; 00069 joint_msg.ns="joint"; 00070 marker_msg.id = 0; 00071 joint_msg.id = 0; 00072 marker_msg.type = visualization_msgs::Marker::LINE_LIST; 00073 joint_msg.type = visualization_msgs::Marker::SPHERE; 00074 marker_msg.scale.x = 0.005; 00075 joint_msg.scale.x = joint_msg.scale.y = joint_msg.scale.z = 0.015; 00076 joint_msg.color.r = .0f; 00077 joint_msg.color.g = 1.0f; 00078 joint_msg.color.b = 1.0f; 00079 joint_msg.color.a = 0.7f; 00080 marker_msg.action = joint_msg.action = visualization_msgs::Marker::ADD; 00081 marker_msg.lifetime = joint_msg.lifetime = ros::Duration(0.1); 00082 00083 HandList hands = frame.hands(); 00084 for (HandList::const_iterator hl = hands.begin(); hl != hands.end(); ++hl) { 00085 // Get the first hand 00086 const Hand hand = *hl; 00087 // Get the Arm bone 00088 // Get fingers 00089 const FingerList fingers = hand.fingers(); 00090 for (FingerList::const_iterator fl = fingers.begin(); fl != fingers.end(); ++fl) { 00091 const Finger finger = *fl; 00092 // Get finger bones 00093 for (int b = 0; b < 4; ++b) { 00094 Bone::Type boneType = static_cast<Bone::Type>(b); 00095 Bone bone = finger.bone(boneType); 00096 geometry_msgs::Point point; 00097 point.x = -bone.prevJoint().x/1000; 00098 point.y = bone.prevJoint().z/1000; 00099 point.z = bone.prevJoint().y/1000; 00100 marker_msg.points.push_back(point); 00101 point.x = joint_msg.pose.position.x = -bone.nextJoint().x/1000; 00102 point.y = joint_msg.pose.position.y = bone.nextJoint().z/1000; 00103 point.z = joint_msg.pose.position.z = bone.nextJoint().y/1000; 00104 marker_msg.points.push_back(point); 00105 joint_msg.id = joint_msg.id+1; 00106 marker_array_msg.markers.push_back(joint_msg); 00107 std_msgs::ColorRGBA color; 00108 color.r = 1.0f; color.g=.0f; color.b=.0f, color.a=1.0f; 00109 marker_msg.colors.push_back(color); 00110 marker_msg.colors.push_back(color); 00111 } 00112 } 00113 } 00114 _pub_marker_array.publish(marker_array_msg); 00115 _pub_bone_only.publish(marker_msg); 00116 } 00117 00118 void HandsListener::onFocusGained(const Controller& controller) { 00119 std::cout << "Focus Gained" << std::endl; 00120 } 00121 00122 void HandsListener::onFocusLost(const Controller& controller) { 00123 std::cout << "Focus Lost" << std::endl; 00124 } 00125 00126 void HandsListener::onDeviceChange(const Controller& controller) { 00127 std::cout << "Device Changed" << std::endl; 00128 const DeviceList devices = controller.devices(); 00129 00130 for (int i = 0; i < devices.count(); ++i) { 00131 std::cout << "id: " << devices[i].toString() << std::endl; 00132 std::cout << " isStreaming: " << (devices[i].isStreaming() ? "true" : "false") << std::endl; 00133 } 00134 } 00135 00136 void HandsListener::onServiceConnect(const Controller& controller) { 00137 std::cout << "Service Connected" << std::endl; 00138 } 00139 00140 void HandsListener::onServiceDisconnect(const Controller& controller) { 00141 std::cout << "Service Disconnected" << std::endl; 00142 } 00143 00144 int main(int argc, char** argv) { 00145 ros::init(argc, argv, "leap_sender"); 00146 // Create a sample listener and controller 00147 HandsListener listener; 00148 Controller controller; 00149 00150 // Have the sample listener receive events from the controller 00151 controller.addListener(listener); 00152 00153 controller.setPolicyFlags(static_cast<Leap::Controller::PolicyFlag> (Leap::Controller::POLICY_IMAGES)); 00154 ros::spin(); 00155 // Remove the sample listener when done 00156 controller.removeListener(listener); 00157 00158 return 0; 00159 }