matcher.h
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------------------------*\
00002    This file contains material supporting chapter 9 of the cookbook:  
00003    Computer Vision Programming using the OpenCV Library. 
00004    by Robert Laganiere, Packt Publishing, 2011.
00005 
00006    This program is free software; permission is hereby granted to use, copy, modify, 
00007    and distribute this source code, or portions thereof, for any purpose, without fee, 
00008    subject to the restriction that the copyright notice may not be removed 
00009    or altered from any source or altered source distribution. 
00010    The software is released on an as-is basis and without any warranties of any kind. 
00011    In particular, the software is not guaranteed to be fault-tolerant or free from failure. 
00012    The author disclaims all warranties with regard to this software, any use, 
00013    and any consequent failure, is purely the responsibility of the user.
00014  
00015    Copyright (C) 2010-2011 Robert Laganiere, www.laganiere.name
00016 \*------------------------------------------------------------------------------------------*/
00017 
00018 #ifndef MATCHER
00019 #define MATCHER
00020 
00021 #include <vector>
00022 #include <opencv2/core/core.hpp>
00023 #include <opencv2/imgproc/imgproc.hpp>
00024 #include <opencv2/highgui/highgui.hpp>
00025 #include <opencv2/features2d/features2d.hpp>
00026 #include <opencv2/nonfree/features2d.hpp>
00027 #include <opencv2/legacy/legacy.hpp>
00028 
00029 class RobustMatcher {
00030 
00031   private:
00032 
00033           // pointer to the feature point detector object
00034           cv::Ptr<cv::FeatureDetector> detector;
00035           // pointer to the feature descriptor extractor object
00036           cv::Ptr<cv::DescriptorExtractor> extractor;
00037           float ratio; // max ratio between 1st and 2nd NN
00038           bool refineF; // if true will refine the F matrix
00039           double distance; // min distance to epipolar
00040           double confidence; // confidence level (probability)
00041       bool verbose; //print stuff or not
00042 
00043   public:
00044 
00045       RobustMatcher() : ratio(0.65f), refineF(true), distance(3.0),confidence(0.99), verbose(false) {
00046 
00047                   // SURF is the default feature
00048                   detector= new cv::SurfFeatureDetector();
00049                   extractor= new cv::SurfDescriptorExtractor();
00050           }
00051 
00052           // Set the feature detector
00053           void setFeatureDetector(cv::Ptr<cv::FeatureDetector>& detect) {
00054 
00055                   detector= detect;
00056           }
00057 
00058       //set verbose
00059       void setVerbose(bool verb)
00060       {
00061           verbose = verb;
00062       }
00063 
00064           // Set descriptor extractor
00065           void setDescriptorExtractor(cv::Ptr<cv::DescriptorExtractor>& desc) {
00066 
00067                   extractor= desc;
00068           }
00069 
00070           // Set the minimum distance to epipolar in RANSAC
00071           void setMinDistanceToEpipolar(double d) {
00072 
00073                   distance= d;
00074           }
00075 
00076           // Set confidence level in RANSAC
00077           void setConfidenceLevel(double c) {
00078 
00079                   confidence= c;
00080           }
00081 
00082           // Set the NN ratio
00083           void setRatio(float r) {
00084 
00085                   ratio= r;
00086           }
00087 
00088           // if you want the F matrix to be recalculated
00089           void refineFundamental(bool flag) {
00090 
00091                   refineF= flag;
00092           }
00093 
00094           // Clear matches for which NN ratio is > than threshold
00095           // return the number of removed points 
00096           // (corresponding entries being cleared, i.e. size will be 0)
00097           int ratioTest(std::vector<std::vector<cv::DMatch> >& matches) {
00098 
00099                 int removed=0;
00100 
00101         // for all matches
00102                 for (std::vector<std::vector<cv::DMatch> >::iterator matchIterator= matches.begin();
00103                          matchIterator!= matches.end(); ++matchIterator) {
00104 
00105                                  // if 2 NN has been identified
00106                                  if (matchIterator->size() > 1) {
00107 
00108                                          // check distance ratio
00109                                          if ((*matchIterator)[0].distance/(*matchIterator)[1].distance > ratio) {
00110 
00111                                                  matchIterator->clear(); // remove match
00112                                                  removed++;
00113                                          }
00114 
00115                                  } else { // does not have 2 neighbours
00116 
00117                                          matchIterator->clear(); // remove match
00118                                          removed++;
00119                                  }
00120                 }
00121 
00122                 return removed;
00123           }
00124 
00125           // Insert symmetrical matches in symMatches vector
00126           void symmetryTest(const std::vector<std::vector<cv::DMatch> >& matches1,
00127                                 const std::vector<std::vector<cv::DMatch> >& matches2,
00128                                             std::vector<cv::DMatch>& symMatches) {
00129                         
00130                 // for all matches image 1 -> image 2
00131                 for (std::vector<std::vector<cv::DMatch> >::const_iterator matchIterator1= matches1.begin();
00132                          matchIterator1!= matches1.end(); ++matchIterator1) {
00133 
00134                         if (matchIterator1->size() < 2) // ignore deleted matches 
00135                                 continue;
00136 
00137                         // for all matches image 2 -> image 1
00138                         for (std::vector<std::vector<cv::DMatch> >::const_iterator matchIterator2= matches2.begin();
00139                                 matchIterator2!= matches2.end(); ++matchIterator2) {
00140 
00141                                 if (matchIterator2->size() < 2) // ignore deleted matches 
00142                                         continue;
00143 
00144                                 // Match symmetry test
00145                                 if ((*matchIterator1)[0].queryIdx == (*matchIterator2)[0].trainIdx  && 
00146                                         (*matchIterator2)[0].queryIdx == (*matchIterator1)[0].trainIdx) {
00147 
00148                                                 // add symmetrical match
00149                                                 symMatches.push_back(cv::DMatch((*matchIterator1)[0].queryIdx,
00150                                                                                                             (*matchIterator1)[0].trainIdx,
00151                                                                                                             (*matchIterator1)[0].distance));
00152                                                 break; // next match in image 1 -> image 2
00153                                 }
00154                         }
00155                 }
00156           }
00157 
00158           // Identify good matches using RANSAC
00159           // Return fundemental matrix
00160           cv::Mat ransacTest(const std::vector<cv::DMatch>& matches,
00161                                  const std::vector<cv::KeyPoint>& keypoints1, 
00162                                                  const std::vector<cv::KeyPoint>& keypoints2,
00163                                              std::vector<cv::DMatch>& outMatches) {
00164 
00165                 // Convert keypoints into Point2f       
00166                 std::vector<cv::Point2f> points1, points2;      
00167                 for (std::vector<cv::DMatch>::const_iterator it= matches.begin();
00168                          it!= matches.end(); ++it) {
00169 
00170                          // Get the position of left keypoints
00171                          float x= keypoints1[it->queryIdx].pt.x;
00172                          float y= keypoints1[it->queryIdx].pt.y;
00173                          points1.push_back(cv::Point2f(x,y));
00174                          // Get the position of right keypoints
00175                          x= keypoints2[it->trainIdx].pt.x;
00176                          y= keypoints2[it->trainIdx].pt.y;
00177                          points2.push_back(cv::Point2f(x,y));
00178             }
00179         cv::Mat fundemental;
00180                 // Compute F matrix using RANSAC
00181                 std::vector<uchar> inliers(points1.size(),0);
00182         if (inliers.size()<8)
00183         {
00184             if(verbose)
00185                 std::cout << "Too few matches" << std::endl;
00186             return fundemental;
00187         }
00188         fundemental= cv::findFundamentalMat(
00189                         cv::Mat(points1),cv::Mat(points2), // matching points
00190                     inliers,      // match status (inlier ou outlier)  
00191                     CV_FM_RANSAC, // RANSAC method
00192                     distance,     // distance to epipolar line
00193                     confidence);  // confidence probability
00194         
00195                 // extract the surviving (inliers) matches
00196                 std::vector<uchar>::const_iterator itIn= inliers.begin();
00197                 std::vector<cv::DMatch>::const_iterator itM= matches.begin();
00198                 // for all matches
00199                 for ( ;itIn!= inliers.end(); ++itIn, ++itM) {
00200 
00201                         if (*itIn) { // it is a valid match
00202 
00203                                 outMatches.push_back(*itM);
00204                         }
00205                 }
00206         if(verbose)
00207             std::cout << "Number of matched points (after cleaning): " << outMatches.size() << std::endl;
00208 
00209                 if (refineF) {
00210                 // The F matrix will be recomputed with all accepted matches
00211 
00212                         // Convert keypoints into Point2f for final F computation       
00213                         points1.clear();
00214                         points2.clear();
00215         
00216                         for (std::vector<cv::DMatch>::const_iterator it= outMatches.begin();
00217                                  it!= outMatches.end(); ++it) {
00218 
00219                                  // Get the position of left keypoints
00220                                  float x= keypoints1[it->queryIdx].pt.x;
00221                                  float y= keypoints1[it->queryIdx].pt.y;
00222                                  points1.push_back(cv::Point2f(x,y));
00223                                  // Get the position of right keypoints
00224                                  x= keypoints2[it->trainIdx].pt.x;
00225                                  y= keypoints2[it->trainIdx].pt.y;
00226                                  points2.push_back(cv::Point2f(x,y));
00227                         }
00228 
00229                         // Compute 8-point F from all accepted matches
00230                         fundemental= cv::findFundamentalMat(
00231                                 cv::Mat(points1),cv::Mat(points2), // matching points
00232                                 CV_FM_8POINT); // 8-point method
00233                 }
00234 
00235                 return fundemental;
00236           }
00237 
00238       // Match feature points using symmetry test and RANSAC
00239       // returns fundemental matrix
00240       cv::Mat match(cv::Mat& image1, cv::Mat& image2, // input images
00241           std::vector<cv::DMatch>& matches, // output matches and keypoints
00242           std::vector<cv::KeyPoint>& keypoints1, std::vector<cv::KeyPoint>& keypoints2) {
00243 
00244         // 1a. Detection of the features
00245         detector->detect(image1,keypoints1);
00246         detector->detect(image2,keypoints2);
00247         if(verbose)
00248         {
00249             std::cout << "Number of points (1): " << keypoints1.size() << std::endl;
00250             std::cout << "Number of points (2): " << keypoints2.size() << std::endl;
00251         }
00252         // 1b. Extraction of the SURF descriptors
00253         cv::Mat descriptors1, descriptors2;
00254         extractor->compute(image1,keypoints1,descriptors1);
00255         extractor->compute(image2,keypoints2,descriptors2);
00256         if(verbose)
00257             std::cout << "descriptor matrix size: " << descriptors1.rows << " by " << descriptors1.cols << std::endl;
00258 
00259         // 2. Match the two image descriptors
00260 
00261         // Construction of the matcher
00262         cv::BruteForceMatcher<cv::L2<float> > matcher;
00263 
00264         // from image 1 to image 2
00265         // based on k nearest neighbours (with k=2)
00266         std::vector<std::vector<cv::DMatch> > matches1;
00267         matcher.knnMatch(descriptors1,descriptors2,
00268             matches1, // vector of matches (up to 2 per entry)
00269             2);           // return 2 nearest neighbours
00270 
00271         // from image 2 to image 1
00272         // based on k nearest neighbours (with k=2)
00273         std::vector<std::vector<cv::DMatch> > matches2;
00274         matcher.knnMatch(descriptors2,descriptors1,
00275             matches2, // vector of matches (up to 2 per entry)
00276             2);           // return 2 nearest neighbours
00277         if(verbose)
00278         {
00279             std::cout << "Number of matched points 1->2: " << matches1.size() << std::endl;
00280             std::cout << "Number of matched points 2->1: " << matches2.size() << std::endl;
00281         }
00282         // 3. Remove matches for which NN ratio is > than threshold
00283 
00284         // clean image 1 -> image 2 matches
00285         int removed= ratioTest(matches1);
00286         if(verbose)
00287             std::cout << "Number of matched points 1->2 (ratio test) : " << matches1.size()-removed << std::endl;
00288         // clean image 2 -> image 1 matches
00289         removed= ratioTest(matches2);
00290         if(verbose)
00291             std::cout << "Number of matched points 1->2 (ratio test) : " << matches2.size()-removed << std::endl;
00292 
00293         // 4. Remove non-symmetrical matches
00294         std::vector<cv::DMatch> symMatches;
00295         symmetryTest(matches1,matches2,symMatches);
00296 
00297         if(verbose)
00298             std::cout << "Number of matched points (symmetry test): " << symMatches.size() << std::endl;
00299 
00300         // 5. Validate matches using RANSAC
00301         cv::Mat fundemental= ransacTest(symMatches, keypoints1, keypoints2, matches);
00302 
00303         // return the found fundemental matrix
00304         return fundemental;
00305     }
00306 
00307       // Match feature points using symmetry test and RANSAC
00308       // returns fundemental matrix
00309       cv::Mat match(std::vector<cv::DMatch>& matches, // output matches and keypoints
00310                     std::vector<cv::KeyPoint>& keypoints1, std::vector<cv::KeyPoint>& keypoints2,
00311                     cv::Mat descriptors1,cv::Mat descriptors2) {
00312 
00313         // 2. Match the two image descriptors
00314 
00315         // Construction of the matcher
00316         cv::BruteForceMatcher<cv::L2<float> > matcher;
00317 
00318         // from image 1 to image 2
00319         // based on k nearest neighbours (with k=2)
00320         std::vector<std::vector<cv::DMatch> > matches1;
00321         matcher.knnMatch(descriptors1,descriptors2,
00322             matches1, // vector of matches (up to 2 per entry)
00323             2);           // return 2 nearest neighbours
00324 
00325         // from image 2 to image 1
00326         // based on k nearest neighbours (with k=2)
00327         std::vector<std::vector<cv::DMatch> > matches2;
00328         matcher.knnMatch(descriptors2,descriptors1,
00329             matches2, // vector of matches (up to 2 per entry)
00330             2);           // return 2 nearest neighbours
00331         if(verbose)
00332         {
00333             std::cout << "Number of matched points 1->2: " << matches1.size() << std::endl;
00334             std::cout << "Number of matched points 2->1: " << matches2.size() << std::endl;
00335         }
00336         // 3. Remove matches for which NN ratio is > than threshold
00337 
00338         // clean image 1 -> image 2 matches
00339         int removed= ratioTest(matches1);
00340         if(verbose)
00341             std::cout << "Number of matched points 1->2 (ratio test) : " << matches1.size()-removed << std::endl;
00342         // clean image 2 -> image 1 matches
00343         removed= ratioTest(matches2);
00344         if(verbose)
00345             std::cout << "Number of matched points 1->2 (ratio test) : " << matches2.size()-removed << std::endl;
00346 
00347         // 4. Remove non-symmetrical matches
00348         std::vector<cv::DMatch> symMatches;
00349         symmetryTest(matches1,matches2,symMatches);
00350 
00351         if(verbose)
00352             std::cout << "Number of matched points (symmetry test): " << symMatches.size() << std::endl;
00353 
00354         // 5. Validate matches using RANSAC
00355         cv::Mat fundemental= ransacTest(symMatches, keypoints1, keypoints2, matches);
00356 
00357         // return the found fundemental matrix
00358         return fundemental;
00359     }
00360 };
00361 
00362 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


lib_rgbdtools
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:33:54