00001 #ifndef FACE_CONTOUR_DETECTOR_FILTERS_EDGECONNECTOR_H_ 00002 #define FACE_CONTOUR_DETECTOR_FILTERS_EDGECONNECTOR_H_ 00003 00004 #include <face_contour_detector/filters/Filter.h> 00005 #include <face_contour_detector/filters/Parameter.h> 00006 #include <vector> 00007 #include <string> 00008 #include <ros/ros.h> 00009 #include <opencv/cv.h> 00010 00011 namespace face_contour_detector { 00012 namespace filters { 00016 class EdgeConnector : public Filter { 00017 public: 00018 EdgeConnector(ros::NodeHandle& node); 00019 00020 virtual std::vector<filters::Parameter> GetParameters(); 00021 virtual void Apply(const cv::Mat& input, cv::Mat& result); 00022 virtual void ResetParameters(); 00023 virtual const std::string& GetFilterName(); 00024 protected: 00025 int m_searchRadius; 00026 00027 ros::ServiceClient m_client; 00028 sensor_msgs::CvBridge m_cvBridge; 00029 //static 00030 static std::string m_filterName; 00031 }; 00032 } //namespace face_contour_detector 00033 } //namespace filters 00034 00035 #endif //FACE_CONTOUR_DETECTOR_FILTERS_EDGECONNECTOR_H_