AreaParameterChooserWorker.h
Go to the documentation of this file.
00001 #ifndef FACE_CONTOUR_DETECTOR_AREAPARAMETERWORKER_H_
00002 #define FACE_CONTOUR_DETECTOR_AREAPARAMETERWORKER_H_
00003 
00004 #include <ros/ros.h>
00005 
00006 #include <opencv/cv.h>
00007 #include <opencv/highgui.h>
00008 #include <sensor_msgs/Image.h>
00009 #include <cv_bridge/CvBridge.h>
00010 #include <image_transport/image_transport.h>
00011 
00012 //service definitions
00013 #include <face_contour_detector/GetFilters.h>
00014 #include <face_contour_detector/ApplyFilters.h>
00015 #include <face_contour_detector/FindFaceAreas.h>
00016 #include <face_contour_detector/autoselect_result.h>
00017 
00018 #include <portrait_robot_msgs/alubsc_node_instr.h>
00019 #include <portrait_robot_msgs/alubsc_status_msg.h>
00020 
00021 
00022 //std
00023 #include <vector>
00024 #include <queue>
00025 
00026 //
00027 #include <face_contour_detector/AutoParameterExplorer.h>
00028 #include <face_contour_detector/KdTree.h>
00029 
00030 #include <boost/function.hpp>
00031 
00032 namespace face_contour_detector {
00034         class AreaParameterChooserWorker {
00035         public:
00041                 AreaParameterChooserWorker(ros::NodeHandle& node, cv::Mat& image, cv::Mat& mask, const std::map<std::string, std::map<std::string, double> >& targetValue);
00042 
00047                 void CallculateParameters(int numResults, int steps, std::vector<face_contour_detector::autoselect_result>& result);
00048 
00049         private:
00051                 void ParamsFunction(const std::vector<double>& params, std::map<std::string, double>& result);
00052                 double CostFunction(const std::map<std::string, double>& result, const std::map<std::string, double>& targetValue);
00053 
00054                 void PushFilterSetup(std::map<std::string, std::vector<std::map<std::string, double> > >& params, int numResults, std::vector<face_contour_detector::autoselect_result>& result);
00055 
00060                 void ApplyFilters(const std::vector<double>& params, std::vector<face_contour_detector::filter_area_result>& results);
00061 
00063                 void GetAreas();
00064 
00067                 void SendStatusMessage(const std::string& message);
00068 
00069                 ros::NodeHandle& node;
00070                 cv::Mat& image;
00071                 cv::Mat bwimage;
00072                 cv::Mat& mask;
00073 
00074                 std::vector<face_contour_detector::image_area> areas;
00075                 std::vector<face_contour_detector::image_area>::iterator currArea;
00076 
00077                 std::map<std::string, std::map<std::string, double> > targetValue;
00078 
00079                 face_contour_detector::KdTree<double, std::map<std::string, double> > kdTree;
00080         };
00081 
00082 } //namespace face_contour_detector
00083 
00084 #endif //FACE_CONTOUR_DETECTOR_AREAPARAMETERWORKER_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


face_contour_detector
Author(s): Fabian Wenzelmann and Julian Schmid
autogenerated on Wed Dec 26 2012 16:18:17