image_processor.h
Go to the documentation of this file.
00001 
00013 #ifndef UCL_DRONE_IMAGE_PROCESSOR_H
00014 #define UCL_DRONE_IMAGE_PROCESSOR_H
00015 
00016 #include <ucl_drone/computer_vision/computer_vision.h>
00017 /*  \class ImageProcessor
00018  *  \brief Class of the image processor node for ROS.
00019  */
00020 class ImageProcessor
00021 {
00022 private:
00023   ros::NodeHandle nh_;
00024 
00025   // Subscribers
00026   image_transport::ImageTransport it_;
00027   image_transport::Subscriber image_sub_;
00028   std::string video_channel_;
00029   ros::Subscriber pose_sub;
00030   std::string pose_channel;
00031   ros::Subscriber reset_pose_sub;
00032   std::string reset_pose_channel;
00033   ros::Subscriber end_reset_pose_sub;
00034   std::string end_reset_pose_channel;
00035 
00036   // Publishers
00037   ros::Publisher processed_image_pub;
00038   std::string processed_image_channel_out;
00039 
00041   ProcessedImage* prev_cam_img;
00042 
00044   bool use_OpticalFlowPyrLK;
00045 
00047   bool target_loaded;
00048 
00050   bool pending_reset;
00051 
00053   Target target;
00054 
00056   void imageCb(const sensor_msgs::Image::ConstPtr& msg);
00057 
00059   void poseCb(const ucl_drone::Pose3D::ConstPtr& posePtr);
00060 
00062   void resetPoseCb(const std_msgs::Empty& msg);
00063 
00065   void endResetPoseCb(const std_msgs::Empty& msg);
00066 
00068   void navdataCb(const ardrone_autonomy::Navdata::ConstPtr navdataPtr);
00069 
00070   ucl_drone::Pose3D::ConstPtr lastPoseReceived;    
00071   ardrone_autonomy::Navdata lastNavdataReceived;   
00072   sensor_msgs::Image::ConstPtr lastImageReceived;  
00073 
00074 public:
00076   ImageProcessor();
00077 
00079   ~ImageProcessor();
00080 
00081   void publishProcessedImg();  
00082 
00083 
00084   bool pose_publishing;   
00085   bool video_publishing;  
00086 };
00087 
00088 #endif /*UCL_DRONE_IMAGE_PROCESSOR_H*/


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