Features.h
Go to the documentation of this file.
00001 /*
00002  * Features.h
00003  *
00004  *  Created on: Oct 16, 2010
00005  *      Author: ethan
00006  */
00007 
00008 #ifndef PANO_FEATURES_H_
00009 #define PANO_FEATURES_H_
00010 
00011 #include <opencv2/core/core.hpp>
00012 #include <opencv2/features2d/features2d.hpp>
00013 
00014 #include <pano_core/pano_interfaces.h>
00015 
00016 #include <typeinfo>
00017 
00018 namespace pano
00019 {
00020 
00021 class Features : public serializable
00022 {
00023 public:
00024 
00025   Features();
00026   virtual ~Features()
00027   {
00028   }
00029 
00030   Features(const Features& rhs)
00031   {
00032     copyData(rhs);
00033   }
00034 
00035   Features& operator=(const Features& rhs)
00036   {
00037     if (this != &rhs)
00038     {
00039       copyData(rhs);
00040     }
00041     return *this;
00042   }
00043 
00044   void detect(const cv::FeatureDetector& detect, const cv::Mat& img);
00045 
00046   cv::Ptr<cv::DescriptorMatcher> makeMatcher() const{
00047     return matcher_->clone(true);//matcher_copier_->clone(*matcher_);
00048   }
00049   template<typename T>
00050     void addMatcher(const T& matcher)
00051     {
00052       matcher_copier_ = cv::Ptr<Copier<cv::DescriptorMatcher> >(new SCopier<T, cv::DescriptorMatcher> ());
00053       matcher_ = cv::Ptr<cv::DescriptorMatcher>(new T(matcher));
00054     }
00055 
00056   template<typename T>
00057     void extract(const cv::DescriptorExtractor& extracter, const cv::Mat& img, const T& matcher)
00058     {
00059       addMatcher(matcher);
00060       extract(extracter, img);
00061     }
00062 
00063   void match(const Features& features, const cv::Mat& mask, std::vector<cv::DMatch>& matches) const;
00064 
00065   cv::Mat& descriptors()
00066   {
00067     return descriptors_;
00068   }
00069   const cv::Mat& descriptors() const
00070   {
00071     return descriptors_;
00072   }
00073 
00074   std::vector<cv::KeyPoint>& kpts()
00075   {
00076     return kpts_;
00077   }
00078   const std::vector<cv::KeyPoint>& kpts() const
00079   {
00080     return kpts_;
00081   }
00082   std::vector<cv::Point2f>& pts()
00083   {
00084     return pts_;
00085   }
00086   const std::vector<cv::Point2f>& pts() const
00087   {
00088     return pts_;
00089   }
00090   /*
00091    * serializable functions
00092    */
00093   virtual int version() const
00094   {
00095     return 0;
00096   }
00097 
00098   virtual void serialize(cv::FileStorage& fs) const;
00099   virtual void deserialize(const cv::FileNode& fn);
00100 
00101 private:
00102 
00103   void extract(const cv::DescriptorExtractor& extract, const cv::Mat& img);
00104 
00105   void copyData(const Features& rhs)
00106   {
00107     if (!rhs.descriptors_.empty())
00108       rhs.descriptors_.copyTo(descriptors_);
00109     else
00110       descriptors_ = cv::Mat();
00111 
00112     kpts_ = rhs.kpts_;
00113     pts_ = rhs.pts_;
00114     if(rhs.matcher_copier_)
00115       matcher_ = rhs.matcher_copier_->make();
00116     matcher_copier_ = rhs.matcher_copier_;
00117 
00118 }
00119 
00120   cv::Mat descriptors_;
00121   std::vector<cv::KeyPoint> kpts_;
00122   std::vector<cv::Point2f> pts_;
00123   cv::Ptr<cv::DescriptorMatcher> matcher_;
00124   cv::Ptr<Copier<cv::DescriptorMatcher> > matcher_copier_;
00125 
00126 };
00127 
00128 void drawMatchesRelative(const Features& train, const Features& query, const std::vector<cv::DMatch>& matches,
00129                          cv::Mat& img, const std::vector<unsigned char>& mask = std::vector<unsigned char>());
00130 
00131 }//namespace pano
00132 #endif /* FEATURES_H_ */


pano_core
Author(s): Ethan Rublee
autogenerated on Mon Oct 6 2014 08:04:38