00001 #ifndef FACE_CONTOUR_DETECTOR_FACECONTOURREQUESTHANDLER_H_ 00002 #define FACE_CONTOUR_DETECTOR_FACECONTOURREQUESTHANDLER_H_ 00003 00004 #include <map> 00005 #include <vector> 00006 #include <string> 00007 #include <queue> 00008 #include <ros/ros.h> 00009 #include <portrait_robot_msgs/alubsc_node_instr.h> 00010 #include <sensor_msgs/Image.h> 00011 #include <opencv/cv.h> 00012 00013 namespace face_contour_detector { 00014 00015 class FaceContourRequestHandler { 00016 private: 00017 //data type definitions 00018 struct ImageMaskPair { 00019 cv::Mat* image; 00020 cv::Mat* mask; 00021 }; 00022 00023 struct WorkerSetting { 00024 int steps; 00025 int numResults; 00026 std::map<std::string, std::map<std::string, double> > targetValues; 00027 }; 00028 00029 public: 00033 FaceContourRequestHandler(ros::NodeHandle& node, std::string exploreConfigPath); 00034 virtual ~FaceContourRequestHandler(); 00035 00037 void SolveOneRequest(); 00038 00042 bool HandleAlubscRequest(portrait_robot_msgs::alubsc_node_instr::Request &req, portrait_robot_msgs::alubsc_node_instr::Response &res); 00043 00044 private: 00047 void M_SendStatusMessage(const std::string& message); 00048 00051 void M_LoadExploreSettings(std::vector<WorkerSetting>& settings); 00052 00054 std::queue<ImageMaskPair> requests; 00055 ros::NodeHandle& node; 00056 std::string exploreConfigPath; 00057 }; 00058 00059 } 00060 00061 #endif /* FACE_CONTOUR_DETECTOR_FACECONTOURREQUESTHANDLER_H_ */