00001 #ifndef _HECTOR_HEAT_DETECTION_H_ 00002 #define _HECTOR_HEAT_DETECTION_H_ 00003 00004 #include "ros/ros.h" 00005 #include "std_msgs/String.h" 00006 #include <hector_worldmodel_msgs/ImagePercept.h> 00007 #include <image_transport/image_transport.h> 00008 #include <cv_bridge/cv_bridge.h> 00009 #include <opencv2/imgproc/imgproc.hpp> 00010 #include <opencv2/features2d/features2d.hpp> 00011 #include <opencv2/highgui/highgui.hpp> 00012 #include <sensor_msgs/image_encodings.h> 00013 #include <cv_bridge/cv_bridge.h> 00014 #include <thermaleye_msgs/Mapping.h> 00015 00016 #include <dynamic_reconfigure/server.h> 00017 #include <hector_heat_detection/HeatDetectionConfig.h> 00018 00019 using hector_heat_detection::HeatDetectionConfig; 00020 00021 class HeatDetection{ 00022 public: 00023 HeatDetection(); 00024 ~HeatDetection(); 00025 private: 00026 void imageCallback(const sensor_msgs::ImageConstPtr& img, const sensor_msgs::CameraInfoConstPtr& info); 00027 void mappingCallback(const thermaleye_msgs::Mapping& mapping); 00028 void dynRecParamCallback(HeatDetectionConfig &config, uint32_t level); 00029 00030 ros::Publisher pub_; 00031 image_transport::CameraSubscriber sub_; 00032 image_transport::CameraPublisher pub_detection_; 00033 ros::Subscriber sub_mapping_; 00034 00035 dynamic_reconfigure::Server<HeatDetectionConfig> dyn_rec_server_; 00036 00037 bool mappingDefined_; 00038 00039 double minTempVictim_; 00040 double maxTempVictim_; 00041 double minAreaVictim_; 00042 double minDistBetweenBlobs_; 00043 std::string perceptClassId_; 00044 00045 thermaleye_msgs::Mapping mapping_; 00046 00047 int image_count_ ; 00048 00049 cv::Mat img_thres_min_; 00050 cv::Mat img_thres_max_; 00051 cv::Mat img_thres_; 00052 00053 }; 00054 00055 #endif