ObjectDetectorMethod.h
Go to the documentation of this file.
00001 
00033 #ifndef __OBJECT_DETECTOR_METHOD__
00034 #define __OBJECT_DETECTOR_METHOD__
00035 
00036 #include <opencv/cv.h>
00037 #include <vector>
00038 #include "re_msgs/DetectedObject.h"
00039 #include "ObjectModel.h"
00040 #include "CameraBridge.h"
00041 #include "VisualizationManager.h"
00042 
00043 #include "DVision.h"
00044 
00045 
00046 class ObjectDetectorMethod
00047 {
00048 public:
00049 
00054   class DetectionData
00055   {
00056   public:
00057 
00058     // All the data fields must inherit AnyData
00059     struct AnyData
00060     {
00061       bool provided;
00062       AnyData(): provided(false){}
00063     };
00064 
00065     struct SURFdata: public AnyData
00066     {
00067       DVision::SurfSet surfset;
00068     };
00069 
00070     // General parameters
00071     struct Parameters
00072     {
00073       const CameraBridge &camera; // camera intrinsic parameters
00074 
00075       Parameters(const CameraBridge& _cam): camera(_cam){}
00076     };
00077 
00078   public:
00079     const cv::Mat &img;    // reference image to search for objects
00080     Parameters params;     // general parameters
00081     SURFdata surfdata;     // surfs from img
00082 
00083   public:
00084     DetectionData(const cv::Mat &_img, const CameraBridge &_cam)
00085     : img(_img), params(_cam) {}
00086 
00087   };
00088 
00089 public:
00090 
00098   virtual void detect(ObjectDetectorMethod::DetectionData &data,
00099     ObjectModel &model,
00100     re_msgs::DetectedObject &detection) = 0;
00101 
00106   virtual inline void setDebugMode(bool onoff, const std::string &dir)
00107   {
00108     m_debug = onoff;
00109     m_debug_dir = dir;
00110   }
00111 
00116   virtual inline bool debugMode() const { return m_debug; }
00117 
00122   virtual inline void setVisualizationManager(VisualizationManager *vis)
00123   {
00124     m_visualizer = vis;
00125   }
00126 
00130   virtual inline bool visualizationMode() const { return m_visualizer != NULL; }
00131 
00132 protected:
00134 
00139   ObjectDetectorMethod(VisualizationManager *vis = NULL):
00140     m_visualizer(vis){}
00141 
00146   inline void visualize(const cv::Mat &image, const std::string &text = "",
00147     bool hold = false)
00148   {
00149     if(m_visualizer) m_visualizer->show(image, text, hold);
00150   }
00151 
00152 protected:
00154 
00165   void calculatePose(const ObjectModel::Face &face, const std::vector<int>
00166     &face_indices, const DVision::SurfSet &scene_surfset,
00167     const std::vector<int> &scene_indices, const CameraBridge &camera,
00168     cv::Mat &cTo) const;
00169 
00175   void convertPose(const cv::Mat &T, geometry_msgs::Pose &pose) const;
00176 
00184   void convert3DPoints(const ObjectModel::Face &face,
00185     const std::vector<int> &indices,
00186     const cv::Mat &cTo,
00187     std::vector<geometry_msgs::Point> &points3d) const;
00188 
00195   void convert3DPoints(const ObjectModel::Face &face,
00196     const cv::Mat &cTo,
00197     std::vector<geometry_msgs::Point> &points3d) const;
00198 
00206   void get3DModelPoints(const ObjectModel::Face &face,
00207     const std::vector<int> &indices,
00208     std::vector<geometry_msgs::Point> &points3d) const;
00209 
00215   void get3DModelPoints(const ObjectModel::Face &face,
00216     std::vector<geometry_msgs::Point> &points3d) const;
00217 
00224   void getPointsOctave(const ObjectModel::Face &face,
00225     const std::vector<int> &indices,
00226     std::vector<int> &octave) const;
00227 
00233    void getPointsOctave(const ObjectModel::Face &face,
00234     std::vector<int> &octave) const;
00235 
00248    void project2DPoints(const ObjectModel::Face &face,
00249     const cv::Mat &cTo, const CameraBridge &camera,
00250     const std::vector<int> &indices,
00251     std::vector<re_msgs::Pixel> &points2d)  const;
00252 
00264   void project2DPoints(const ObjectModel::Face &face,
00265     const cv::Mat &cTo, const CameraBridge &camera,
00266     std::vector<re_msgs::Pixel> &points2d) const;
00267 
00276   void changeOrientation(const cv::Mat &cTo, cv::Mat &rTo) const;
00277 
00278 protected:
00279 
00280   bool m_debug; 
00281   std::string m_debug_dir; 
00282 
00283   VisualizationManager *m_visualizer;
00284 
00285 };
00286 
00287 #endif


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