leap_camera.cpp
Go to the documentation of this file.
00001 #include <iostream>
00002 #include <string.h>
00003 #include "Leap.h"
00004 #include "ros/ros.h"
00005 #include "sensor_msgs/Image.h"
00006 #include "sensor_msgs/CameraInfo.h"
00007 #include "camera_info_manager/camera_info_manager.h"
00008 #include "rospack/rospack.h"
00009 
00010 #include <boost/shared_ptr.hpp>
00011 #include <sstream>
00012 
00013 /* ##################################################
00014     Deprecated and will be removed in the future  
00015 ################################################## */
00016 
00017 #define targetWidth 500
00018 #define targetHeight 500
00019 #define cutWidth 280
00020 #define cutHeight 220
00021 #define startX 110
00022 #define startY 140
00023 
00024 using namespace Leap;
00025 using namespace std;
00026 
00027 
00028 
00029 class CameraListener : public Listener {
00030   public:
00031   //ros::NodeHandle _node;
00032   boost::shared_ptr <ros::NodeHandle> _left_node;
00033   boost::shared_ptr <ros::NodeHandle> _right_node;
00034   
00035   ros::Publisher _pub_image_left;
00036   ros::Publisher _pub_info_left;
00037   ros::Publisher _pub_image_right;
00038   ros::Publisher _pub_info_right;
00039   camera_info_manager::CameraInfoManager* info_mgr_right;
00040   camera_info_manager::CameraInfoManager* info_mgr_left;
00041   unsigned int seq;
00042   virtual void onInit(const Controller&);
00043   virtual void onConnect(const Controller&);
00044   virtual void onDisconnect(const Controller&);
00045   virtual void onExit(const Controller&);
00046   virtual void onFrame(const Controller&);
00047   virtual void onFocusGained(const Controller&);
00048   virtual void onFocusLost(const Controller&);
00049   virtual void onDeviceChange(const Controller&);
00050   virtual void onServiceConnect(const Controller&);
00051   virtual void onServiceDisconnect(const Controller&);  
00052   private:
00053 };
00054 
00055 
00056 void CameraListener::onInit(const Controller& controller){
00057 
00058   _left_node = boost::make_shared<ros::NodeHandle>("left");
00059   _right_node = boost::make_shared<ros::NodeHandle>("right");
00060   std::cout << "Initialized" << std::endl;
00061   _pub_image_left = _left_node->advertise<sensor_msgs::Image>("image_raw", 1);
00062   _pub_info_left = _left_node->advertise<sensor_msgs::CameraInfo>("camera_info", 1);
00063   _pub_image_right = _right_node->advertise<sensor_msgs::Image>("image_raw", 1);
00064   _pub_info_right = _right_node->advertise<sensor_msgs::CameraInfo>("camera_info", 1);
00065   seq = 0;
00066   std::string default_l_info_filename;
00067   std::string default_r_info_filename;
00068   rospack::Rospack rp;
00069   std::vector<std::string> search_path;
00070   rp.getSearchPathFromEnv(search_path);
00071   rp.crawl(search_path, 1);
00072   std::string path;
00073   if (rp.find("leap_motion",path)==true) {
00074     default_l_info_filename = path + std::string("/config/camera_info/leap_cal_left.yml");
00075     default_r_info_filename = path + std::string("/config/camera_info/leap_cal_right.yml");
00076   }
00077   else {
00078     default_l_info_filename = "";
00079     default_r_info_filename = "";
00080   }
00081   ros::NodeHandle local_nh("~");
00082   std::string l_info_filename;
00083   std::string r_info_filename;
00084   local_nh.param("template_filename_left", l_info_filename, default_l_info_filename);
00085   local_nh.param("template_filename_right", r_info_filename, default_r_info_filename);
00086   l_info_filename = std::string("file://") + l_info_filename;
00087   r_info_filename = std::string("file://") + r_info_filename;
00088   info_mgr_left = new camera_info_manager::CameraInfoManager(*_left_node, "left", l_info_filename);
00089   info_mgr_right = new camera_info_manager::CameraInfoManager(*_right_node, "right", r_info_filename);
00090 }
00091 
00092 void CameraListener::onConnect(const Controller& controller) {
00093   std::cout << "Connected" << std::endl;
00094   controller.enableGesture(Gesture::TYPE_CIRCLE);
00095   controller.enableGesture(Gesture::TYPE_KEY_TAP);
00096   controller.enableGesture(Gesture::TYPE_SCREEN_TAP);
00097   controller.enableGesture(Gesture::TYPE_SWIPE);
00098 }
00099 
00100 void CameraListener::onDisconnect(const Controller& controller) {
00101   // Note: not dispatched when running in a debugger.
00102   std::cout << "Disconnected" << std::endl;
00103 }
00104 
00105 void CameraListener::onExit(const Controller& controller) {
00106   std::cout << "Exited" << std::endl;
00107 }
00108 
00109 void CameraListener::onFrame(const Controller& controller) {
00110   // Get the most recent frame and report some basic information
00111   const Frame frame = controller.frame();  
00112   ImageList images = frame.images();
00113 
00114   sensor_msgs::Image image_msg;
00115   image_msg.header.seq = seq++;
00116   image_msg.header.stamp =ros::Time::now();
00117   image_msg.encoding ="mono8";
00118   image_msg.is_bigendian = 0;
00119   for(int camera_num=0; camera_num<2; camera_num++){
00120     Image image = images[camera_num];
00121     image_msg.width =  cutWidth;
00122     image_msg.height = cutHeight;
00123     image_msg.step = cutWidth;
00124     image_msg.data.resize(cutWidth*cutHeight);
00125 #pragma omp parallel for
00126     for(int i=0; i<cutWidth; i++){
00127       for(int j=0; j<cutHeight; j++){
00128         Vector input = Vector((float)(i+startX)/targetWidth, (float)(j+startY)/targetHeight, 0);
00129         input.x = (input.x - image.rayOffsetX()) / image.rayScaleX();
00130         input.y = (input.y - image.rayOffsetY()) / image.rayScaleY();
00131         Vector pixel = image.warp(input);
00132         if(pixel.x >= 0 && pixel.x < image.width() && pixel.y >= 0 && pixel.y < image.height()) {
00133           int data_index = floor(pixel.y) * image.width() + floor(pixel.x);
00134           image_msg.data[cutWidth*j+i] = image.data()[data_index];
00135         } else {
00136           image_msg.data[cutWidth*j+i] = 0;
00137         }
00138       }
00139     }
00140     if(camera_num==0){
00141       sensor_msgs::CameraInfoPtr info_msg(new sensor_msgs::CameraInfo(info_mgr_left->getCameraInfo()));
00142       image_msg.header.frame_id = info_msg->header.frame_id ="leap_optical_frame";
00143       info_msg->width = image_msg.width;
00144       info_msg->height = image_msg.height;
00145       info_msg->header.stamp = image_msg.header.stamp;
00146       info_msg->header.seq = image_msg.header.seq;
00147       _pub_image_left.publish(image_msg);
00148       _pub_info_left.publish(*info_msg);
00149     }else{
00150       sensor_msgs::CameraInfoPtr info_msg(new sensor_msgs::CameraInfo(info_mgr_right->getCameraInfo()));
00151       image_msg.header.frame_id = info_msg->header.frame_id = "leap_optical_frame";
00152       info_msg->width = image_msg.width;
00153       info_msg->height = image_msg.height;
00154       info_msg->header.stamp = image_msg.header.stamp;
00155       info_msg->header.seq = image_msg.header.seq;
00156       _pub_image_right.publish(image_msg);
00157       _pub_info_right.publish(*info_msg);
00158     }
00159   }
00160   // test
00161 
00162   //to do
00163   // int start_x = 100;
00164   // int start_y = 100;
00165   // int end_x = 300;
00166   // int end_y = 300;
00167   // int width_x = end_x - start_x;
00168   // int width_y = end_y - start_y;
00169   //     } else {
00170   //    image_msg.data[width_x*(j-start_y)+(i-start_x)] = 255;
00171   //     }
00172   //   }
00173   // }
00174   //end for test
00175 }
00176 
00177 void CameraListener::onFocusGained(const Controller& controller) {
00178   std::cout << "Focus Gained" << std::endl;
00179 }
00180 
00181 void CameraListener::onFocusLost(const Controller& controller) {
00182   std::cout << "Focus Lost" << std::endl;
00183 }
00184 
00185 void CameraListener::onDeviceChange(const Controller& controller) {
00186   std::cout << "Device Changed" << std::endl;
00187   const DeviceList devices = controller.devices();
00188 
00189   for (int i = 0; i < devices.count(); ++i) {
00190     std::cout << "id: " << devices[i].toString() << std::endl;
00191     std::cout << "  isStreaming: " << (devices[i].isStreaming() ? "true" : "false") << std::endl;
00192   }
00193 }
00194 
00195 void CameraListener::onServiceConnect(const Controller& controller) {
00196   std::cout << "Service Connected" << std::endl;
00197 }
00198 
00199 void CameraListener::onServiceDisconnect(const Controller& controller) {
00200   std::cout << "Service Disconnected" << std::endl;
00201 }
00202 
00203 int main(int argc, char** argv) {
00204   ros::init(argc, argv, "leap_sender");
00205   // Create a sample listener and controller
00206   CameraListener listener;
00207   Controller controller;
00208 
00209   
00210   
00211   // Have the sample listener receive events from the controller
00212   controller.addListener(listener);
00213   
00214   controller.setPolicyFlags(static_cast<Leap::Controller::PolicyFlag> (Leap::Controller::POLICY_IMAGES));
00215   ros::spin();
00216   // Remove the sample listener when done
00217   controller.removeListener(listener);
00218 
00219   return 0;
00220 }


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