ObjectDetectorProvider.h
Go to the documentation of this file.
00001 
00034 #ifndef __OBJECT_DETECTOR_PROVIDER__
00035 #define __OBJECT_DETECTOR_PROVIDER__
00036 
00037 #include "ros/ros.h"
00038 #include "std_msgs/String.h"
00039 #include "sensor_msgs/Image.h"
00040 #include "sensor_msgs/CameraInfo.h"
00041 #include "image_transport/image_transport.h"
00042 #include "cv_bridge/CvBridge.h"
00043 #include "re_vision/SearchFor.h"
00044 #include "re_msgs/DetectedObject.h"
00045 #include "CameraBridge.h"
00046 #include <vector>
00047 #include <string>
00048 
00049 #include "ObjectModel.h"
00050 #include "ObjectDetectorMethod.h"
00051 #include "VisualizationManager.h"
00052 
00053 #include <opencv/cv.h>
00054 
00055 
00056 using namespace std;
00057 
00058 class ObjectDetectorProvider
00059 {
00060 public:
00061 
00067   ObjectDetectorProvider(const ros::NodeHandle& node_handle);
00068 
00074   ObjectDetectorProvider(const ros::NodeHandle& node_handle,
00075     const CameraBridge &camera);
00076 
00077         virtual ~ObjectDetectorProvider();
00078 
00079         void init();
00080 
00084         bool ServiceSearchFor(re_vision::SearchFor::Request  &req,
00085                 re_vision::SearchFor::Response &res );
00086 
00090   void TopicNewModel(const std_msgs::String::ConstPtr& msg);
00091 
00095   void TopicCameraInfo(const sensor_msgs::CameraInfo::ConstPtr& caminfo);
00096 
00102   void SetDebugMode(bool onoff, const std::string &dir = "");
00103 
00108   void SetVisualizationMode(bool onoff);
00109 
00110 protected:
00111         // ROS-related functions
00112 
00113         cv::Mat getImage(const re_vision::SearchFor::Request &req);
00114 
00115         void showRequestInformation(const re_vision::SearchFor::Request &req,
00116                 const cv::Mat &image) const;
00117 
00118         //void showImage(const cv::Mat &image) const;
00119 
00120         void processRequest(const re_vision::SearchFor::Request  &req,
00121                 const cv::Mat &image, re_vision::SearchFor::Response &res);
00122 
00123         void emptyResponse(const re_vision::SearchFor::Request &req,
00124           re_vision::SearchFor::Response &res) const;
00125 
00126 protected:
00127         // Detector-related functions
00128 
00132         void createDetectionAlgorithms();
00133 
00138         void learnNewModel(const std::string &path);
00139 
00144         void removeModel(const std::string &name);
00145 
00155         void rectifyDetections(std::vector<re_msgs::DetectedObject> &detections,
00156           int W, int H, int max_points_per_object) const;
00157 
00158         //void removeUnknownObjects(const std::vector<std::string> &objects,
00159         //      std::vector<std::string> &filtered) const;
00160 
00161         //virtual void initLearning() = 0;
00162         //virtual void finishLearning() = 0;
00163 
00164         void detectObjects(const std::vector<std::string> &objects,
00165                              const cv::Mat &image, int max_points_per_object,
00166                              std::vector<re_msgs::DetectedObject*> &ret);
00167 
00173   void removeSomePoints(re_msgs::DetectedObject& detection,
00174     int max_points) const;
00175 
00176         inline bool debugMode() const { return m_debug; }
00177 
00178         // Returns a reference to the camera
00179         inline const CameraBridge& getCamera() const
00180         {
00181                 return m_camera;
00182         }
00183 
00184         void getValidObjects(const std::vector<std::string> &objects,
00185                 std::vector<std::string>& valid_objects,
00186                 std::vector<re_msgs::DetectedObject> &detections,
00187                 std::vector<re_msgs::DetectedObject *> &pointers) const;
00188 
00189         /*
00190 protected:
00191 
00192 
00193         // This function object is executed by another thread.
00194         // It must set m_ready = true when finished
00195         struct asyncLearner
00196         {
00197                 asyncLearner(ObjectDetectorProvider &parent):
00198                         m_parent(parent){}
00199 
00200                 void operator()();
00201 
00202                 private:
00203                         ObjectDetectorProvider& m_parent;
00204         };
00205 
00206 
00207         void asyncLearnModels();
00208         */
00209 
00210 protected:
00211         ros::NodeHandle m_node_handle;
00212         ros::ServiceServer m_service;
00213         ros::Subscriber m_new_model_sub;
00214         ros::Subscriber *m_camera_info_sub;
00215         ros::Publisher m_visualization_pub;
00216         sensor_msgs::CvBridge m_bridge;
00217 
00218 
00219   //std::string m_camera_info_topic;
00220         CameraBridge m_camera;
00221         bool m_camera_info_got;
00222 
00223         //bool m_ready;
00224         bool m_debug;
00225 
00226         // visualization flag
00227         VisualizationManager *m_visualizer;
00228         bool m_visualization;
00229 
00230         //std::vector<ParsedObjectInformation> m_object_list;
00231 
00232         // Map object_name -> object_model
00233         typedef std::map<std::string, ObjectModel*> tModelMap;
00234         tModelMap m_models;
00235 
00236         // Map object_type -> object_detection_algorithm
00237         typedef std::map<std::string, ObjectDetectorMethod*> tAlgorithmMap;
00238         tAlgorithmMap m_algorithms;
00239 
00240 };
00241 
00242 #endif
00243 


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:32:01