vision_gui.h
Go to the documentation of this file.
00001 
00009 #ifndef UCL_DRONE_VISION_GUI_H
00010 #define UCL_DRONE_VISION_GUI_H
00011 
00012 // ROS debug messages
00013 #include <ros/package.h>
00014 #include <ros/ros.h>
00015 
00016 // #define USE_PROFILING
00017 #include <ucl_drone/profiling.h>
00018 
00019 // messages
00020 #include <sensor_msgs/image_encodings.h>
00021 #include <ucl_drone/ProcessedImageMsg.h>
00022 
00023 // vision
00024 #include <cv_bridge/cv_bridge.h>
00025 #include <image_transport/image_transport.h>
00026 #include <opencv2/calib3d/calib3d.hpp>
00027 #include <opencv2/core/core.hpp>
00028 #include <opencv2/highgui/highgui.hpp>
00029 #include <opencv2/imgproc/imgproc.hpp>
00030 #include <opencv2/nonfree/features2d.hpp>
00031 #include <opencv2/nonfree/nonfree.hpp>
00032 
00034 static const std::string OPENCV_WINDOW1 = "Keypoints window";
00035 
00040 class VisionGui
00041 {
00042 private:
00044   ros::NodeHandle nh_;
00045 
00047   bool draw_keypoints;
00048   bool draw_target;
00049 
00051   ros::Subscriber processed_img_sub;
00052   std::string processed_img_channel;
00053 
00055   void processedImageCb(const ucl_drone::ProcessedImageMsg::ConstPtr processed_image);
00056 
00058   void convertMsgToAttributes(ucl_drone::ProcessedImageMsg::ConstPtr msg);
00059 
00061   ucl_drone::ProcessedImageMsg::ConstPtr lastProcessedImgReceived;
00062 
00064   cv_bridge::CvImagePtr cv_ptr;
00065 
00066   std::vector< cv::Point2f > keypoints;
00067   std::vector< cv::Point2f > target_cornersAndCenter;
00068 
00069   bool target_detected;
00070 
00071 public:
00073   VisionGui();
00074 
00076   ~VisionGui();
00077 
00078   void guiDrawKeypoints();
00079 
00080   // bool processed_image_publishing;
00081   bool new_processed_img_available;
00082 };
00083 
00084 #endif /* UCL_DRONE_VISION_GUI_H */


ucl_drone
Author(s): dronesinma
autogenerated on Sat Jun 8 2019 20:51:53