Visual Servoing Platform  version 3.0.0
vpKeyPoint.h
1 /****************************************************************************
2  *
3  * This file is part of the ViSP software.
4  * Copyright (C) 2005 - 2015 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or
7  * modify it under the terms of the GNU General Public License
8  * ("GPL") version 2 as published by the Free Software Foundation.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See http://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  *
30  * Description:
31  * Key point functionalities.
32  *
33  * Authors:
34  * Souriya Trinh
35  *
36  *****************************************************************************/
37 #ifndef __vpKeyPoint_h__
38 #define __vpKeyPoint_h__
39 
40 #include <algorithm> // std::transform
41 #include <vector> // std::vector
42 #include <stdlib.h> // srand, rand
43 #include <time.h> // time
44 #include <fstream> // std::ofstream
45 #include <numeric> // std::accumulate
46 #include <float.h> // DBL_MAX
47 #include <map> // std::map
48 #include <limits>
49 
50 #include <visp3/core/vpConfig.h>
51 #include <visp3/vision/vpBasicKeyPoint.h>
52 #include <visp3/core/vpImageConvert.h>
53 #include <visp3/core/vpPoint.h>
54 #include <visp3/core/vpDisplay.h>
55 #include <visp3/core/vpPlane.h>
56 #include <visp3/core/vpPixelMeterConversion.h>
57 #include <visp3/vision/vpPose.h>
58 #ifdef VISP_HAVE_MODULE_IO
59 # include <visp3/io/vpImageIo.h>
60 #endif
61 #include <visp3/core/vpPolygon.h>
62 #include <visp3/vision/vpXmlConfigParserKeyPoint.h>
63 #include <visp3/core/vpConvert.h>
64 #include <visp3/core/vpMeterPixelConversion.h>
65 
66 // Require at least OpenCV >= 2.1.1
67 #if (VISP_HAVE_OPENCV_VERSION >= 0x020101)
68 
69 #include <opencv2/features2d/features2d.hpp>
70 #include <opencv2/calib3d/calib3d.hpp>
71 #include <opencv2/imgproc/imgproc.hpp>
72 
73 #if defined(VISP_HAVE_OPENCV_XFEATURES2D) // OpenCV >= 3.0.0
74 # include <opencv2/xfeatures2d.hpp>
75 #elif defined(VISP_HAVE_OPENCV_NONFREE) && (VISP_HAVE_OPENCV_VERSION >= 0x020400) && (VISP_HAVE_OPENCV_VERSION < 0x030000)
76 # include <opencv2/nonfree/nonfree.hpp>
77 #endif
78 
79 #ifdef VISP_HAVE_XML2
80 # include <libxml/xmlwriter.h>
81 #endif
82 
213 class VISP_EXPORT vpKeyPoint : public vpBasicKeyPoint {
214 
215 public:
216 
218  typedef enum {
223  noFilterMatching
224  } vpFilterMatchingType;
225 
227  typedef enum {
229  detectionScore
231  } vpDetectionMethodType;
232 
234  typedef enum {
238  pgmImageFormat
239  } vpImageFormatType;
240 
241 
242  vpKeyPoint(const std::string &detectorName="ORB", const std::string &extractorName="ORB",
243  const std::string &matcherName="BruteForce-Hamming", const vpFilterMatchingType &filterType=ratioDistanceThreshold);
244  vpKeyPoint(const std::vector<std::string> &detectorNames, const std::vector<std::string> &extractorNames,
245  const std::string &matcherName="BruteForce", const vpFilterMatchingType &filterType=ratioDistanceThreshold);
246 
247  unsigned int buildReference(const vpImage<unsigned char> &I);
248  unsigned int buildReference(const vpImage<unsigned char> &I,
249  const vpImagePoint &iP, const unsigned int height, const unsigned int width);
250  unsigned int buildReference(const vpImage<unsigned char> &I, const vpRect& rectangle);
251 
252  void buildReference(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &trainKeyPoint,
253  std::vector<cv::Point3f> &points3f, const bool append=false, const int class_id=-1);
254  void buildReference(const vpImage<unsigned char> &I, const std::vector<cv::KeyPoint> &trainKeyPoint,
255  const cv::Mat &trainDescriptors, const std::vector<cv::Point3f> &points3f,
256  const bool append=false, const int class_id=-1);
257 
258  static void compute3D(const cv::KeyPoint &candidate, const std::vector<vpPoint> &roi,
259  const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, cv::Point3f &point);
260 
261  static void compute3D(const vpImagePoint &candidate, const std::vector<vpPoint> &roi,
262  const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, vpPoint &point);
263 
264  static void compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
265  std::vector<cv::KeyPoint> &candidate, const std::vector<vpPolygon> &polygons,
266  const std::vector<std::vector<vpPoint> > &roisPt, std::vector<cv::Point3f> &points, cv::Mat *descriptors=NULL);
267 
268  static void compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam,
269  std::vector<vpImagePoint> &candidate, const std::vector<vpPolygon> &polygons,
270  const std::vector<std::vector<vpPoint> > &roisPt, std::vector<vpPoint> &points, cv::Mat *descriptors=NULL);
271 
272  bool computePose(const std::vector<cv::Point2f> &imagePoints, const std::vector<cv::Point3f> &objectPoints,
273  const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, std::vector<int> &inlierIndex,
274  double &elapsedTime, bool (*func)(vpHomogeneousMatrix *)=NULL);
275 
276  bool computePose(const std::vector<vpPoint> &objectVpPoints, vpHomogeneousMatrix &cMo,
277  std::vector<vpPoint> &inliers, double &elapsedTime, bool (*func)(vpHomogeneousMatrix *)=NULL);
278 
279  bool computePose(const std::vector<vpPoint> &objectVpPoints, vpHomogeneousMatrix &cMo,
280  std::vector<vpPoint> &inliers, std::vector<unsigned int> &inlierIndex,
281  double &elapsedTime, bool (*func)(vpHomogeneousMatrix *)=NULL);
282 
283  void createImageMatching(vpImage<unsigned char> &IRef, vpImage<unsigned char> &ICurrent, vpImage<unsigned char> &IMatching);
284  void createImageMatching(vpImage<unsigned char> &ICurrent, vpImage<unsigned char> &IMatching);
285 
286  void detect(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &keyPoints, double &elapsedTime,
287  const vpRect& rectangle=vpRect());
288  void detect(const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, double &elapsedTime,
289  const cv::Mat &mask=cv::Mat());
290 
291  void detectExtractAffine(const vpImage<unsigned char> &I, std::vector<std::vector<cv::KeyPoint> >& listOfKeypoints,
292  std::vector<cv::Mat>& listOfDescriptors,
293  std::vector<vpImage<unsigned char> > *listOfAffineI=NULL);
294 
295  void display(const vpImage<unsigned char> &IRef, const vpImage<unsigned char> &ICurrent, unsigned int size=3);
296  void display(const vpImage<unsigned char> &ICurrent, unsigned int size=3, const vpColor &color=vpColor::green);
297 
298  void displayMatching(const vpImage<unsigned char> &IRef, vpImage<unsigned char> &IMatching,
299  unsigned int crossSize, unsigned int lineThickness=1,
300  const vpColor &color=vpColor::green);
301  void displayMatching(const vpImage<unsigned char> &ICurrent, vpImage<unsigned char> &IMatching,
302  const std::vector<vpImagePoint> &ransacInliers=std::vector<vpImagePoint>(), unsigned int crossSize=3,
303  unsigned int lineThickness=1);
304 
305  void extract(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
306  double &elapsedTime, std::vector<cv::Point3f> *trainPoints=NULL);
307  void extract(const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
308  double &elapsedTime, std::vector<cv::Point3f> *trainPoints=NULL);
309 
317  inline vpMatrix getCovarianceMatrix() const {
318  if(!m_computeCovariance) {
319  std::cout << "Warning : The covariance matrix has not been computed. See setCovarianceComputation() to do it." << std::endl;
320  return vpMatrix();
321  }
322 
323  if(m_computeCovariance && !m_useRansacVVS) {
324  std::cout << "Warning : The covariance matrix can only be computed with a Virtual Visual Servoing approach." << std::endl
325  << "Use setUseRansacVVS(true) to choose to use a pose estimation method based on a Virtual Visual Servoing approach."
326  << std::endl;
327  return vpMatrix();
328  }
329 
330  return m_covarianceMatrix;
331  }
332 
338  inline double getDetectionTime() const {
339  return m_detectionTime;
340  }
341 
348  inline cv::Ptr<cv::FeatureDetector> getDetector(const std::string &name) const {
349  std::map<std::string, cv::Ptr<cv::FeatureDetector> >::const_iterator findDetector = m_detectors.find(name);
350  if(findDetector != m_detectors.end()) {
351  return findDetector->second;
352  }
353 
354  return cv::Ptr<cv::FeatureDetector>();
355  }
356 
362  inline double getExtractionTime() const {
363  return m_extractionTime;
364  }
365 
372  inline cv::Ptr<cv::DescriptorExtractor> getExtractor(const std::string &name) const {
373  std::map<std::string, cv::Ptr<cv::DescriptorExtractor> >::const_iterator findExtractor = m_extractors.find(name);
374  if(findExtractor != m_extractors.end()) {
375  return findExtractor->second;
376  }
377 
378  return cv::Ptr<cv::DescriptorExtractor>();
379  }
380 
387  return m_imageFormat;
388  }
389 
395  inline double getMatchingTime() const {
396  return m_matchingTime;
397  }
398 
404  inline cv::Ptr<cv::DescriptorMatcher> getMatcher() const {
405  return m_matcher;
406  }
407 
413  inline std::vector<cv::DMatch> getMatches() const {
414  return m_filteredMatches;
415  }
416 
422  inline std::vector<std::pair<cv::KeyPoint, cv::KeyPoint> > getMatchQueryToTrainKeyPoints() const {
423  std::vector<std::pair<cv::KeyPoint, cv::KeyPoint> > matchQueryToTrainKeyPoints(m_filteredMatches.size());
424  for (size_t i = 0; i < m_filteredMatches.size(); i++) {
425  matchQueryToTrainKeyPoints.push_back(std::pair<cv::KeyPoint, cv::KeyPoint>(
426  m_queryFilteredKeyPoints[(size_t) m_filteredMatches[i].queryIdx],
427  m_trainKeyPoints[(size_t) m_filteredMatches[i].trainIdx]));
428  }
429  return matchQueryToTrainKeyPoints;
430  }
431 
437  inline unsigned int getNbImages() const {
438  return static_cast<unsigned int>(m_mapOfImages.size());
439  }
440 
441  void getObjectPoints(std::vector<cv::Point3f> &objectPoints) const;
442  void getObjectPoints(std::vector<vpPoint> &objectPoints) const;
443 
449  inline double getPoseTime() const {
450  return m_poseTime;
451  }
452 
458  inline cv::Mat getQueryDescriptors() const {
459  return m_queryDescriptors;
460  }
461 
462  void getQueryKeyPoints(std::vector<cv::KeyPoint> &keyPoints) const;
463  void getQueryKeyPoints(std::vector<vpImagePoint> &keyPoints) const;
464 
470  inline std::vector<vpImagePoint> getRansacInliers() const {
471  return m_ransacInliers;
472  }
473 
479  inline std::vector<vpImagePoint> getRansacOutliers() const {
480  return m_ransacOutliers;
481  }
482 
488  inline cv::Mat getTrainDescriptors() const {
489  return m_trainDescriptors;
490  }
491 
492  void getTrainKeyPoints(std::vector<cv::KeyPoint> &keyPoints) const;
493  void getTrainKeyPoints(std::vector<vpImagePoint> &keyPoints) const;
494 
495  void getTrainPoints(std::vector<cv::Point3f> &points) const;
496  void getTrainPoints(std::vector<vpPoint> &points) const;
497 
498  void initMatcher(const std::string &matcherName);
499 
500  void insertImageMatching(const vpImage<unsigned char> &IRef, const vpImage<unsigned char> &ICurrent,
501  vpImage<unsigned char> &IMatching);
502  void insertImageMatching(const vpImage<unsigned char> &ICurrent, vpImage<unsigned char> &IMatching);
503 
504 #ifdef VISP_HAVE_XML2
505  void loadConfigFile(const std::string &configFile);
506 #endif
507 
508  void loadLearningData(const std::string &filename, const bool binaryMode=false, const bool append=false);
509 
510  void match(const cv::Mat &trainDescriptors, const cv::Mat &queryDescriptors,
511  std::vector<cv::DMatch> &matches, double &elapsedTime);
512 
513  unsigned int matchPoint(const vpImage<unsigned char> &I);
514  unsigned int matchPoint(const vpImage<unsigned char> &I, const vpImagePoint &iP,
515  const unsigned int height, const unsigned int width);
516  unsigned int matchPoint(const vpImage<unsigned char> &I, const vpRect& rectangle);
517 
519  double &error, double &elapsedTime, bool (*func)(vpHomogeneousMatrix *)=NULL,
520  const vpRect& rectangle=vpRect());
521 
522  bool matchPointAndDetect(const vpImage<unsigned char> &I, vpRect &boundingBox, vpImagePoint &centerOfGravity,
523  const bool isPlanarObject=true, std::vector<vpImagePoint> *imPts1=NULL,
524  std::vector<vpImagePoint> *imPts2=NULL, double *meanDescriptorDistance=NULL,
525  double *detectionScore=NULL, const vpRect& rectangle=vpRect());
526 
527  bool matchPointAndDetect(const vpImage<unsigned char> &I, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo,
528  double &error, double &elapsedTime, vpRect &boundingBox, vpImagePoint &centerOfGravity,
529  bool (*func)(vpHomogeneousMatrix *)=NULL, const vpRect& rectangle=vpRect());
530 
531  void reset();
532 
533  void saveLearningData(const std::string &filename, const bool binaryMode=false, const bool saveTrainingImages=true);
534 
540  inline void setCovarianceComputation(const bool& flag) {
541  m_computeCovariance = flag;
542  if(!m_useRansacVVS) {
543  std::cout << "Warning : The covariance matrix can only be computed with a Virtual Visual Servoing approach." << std::endl
544  << "Use setUseRansacVVS(true) to choose to use a pose estimation method based on a Virtual "
545  "Visual Servoing approach." << std::endl;
546  }
547  }
548 
554  inline void setDetectionMethod(const vpDetectionMethodType &method) {
555  m_detectionMethod = method;
556  }
557 
563  inline void setDetector(const std::string &detectorName) {
564  m_detectorNames.clear();
565  m_detectorNames.push_back(detectorName);
566  m_detectors.clear();
567  initDetector(detectorName);
568  }
569 
570 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
571 
578  template<typename T1, typename T2, typename T3> inline void setDetectorParameter(const T1 detectorName,
579  const T2 parameterName, const T3 value) {
580  if(m_detectors.find(detectorName) != m_detectors.end()) {
581  m_detectors[detectorName]->set(parameterName, value);
582  }
583  }
584 #endif
585 
591  inline void setDetectors(const std::vector<std::string> &detectorNames) {
592  m_detectorNames.clear();
593  m_detectors.clear();
594  m_detectorNames = detectorNames;
595  initDetectors(m_detectorNames);
596  }
597 
603  inline void setExtractor(const std::string &extractorName) {
604  m_extractorNames.clear();
605  m_extractorNames.push_back(extractorName);
606  m_extractors.clear();
607  initExtractor(extractorName);
608  }
609 
610 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
611 
618  template<typename T1, typename T2, typename T3> inline void setExtractorParameter(const T1 extractorName,
619  const T2 parameterName, const T3 value) {
620  if(m_extractors.find(extractorName) != m_extractors.end()) {
621  m_extractors[extractorName]->set(parameterName, value);
622  }
623  }
624 #endif
625 
631  inline void setExtractors(const std::vector<std::string> &extractorNames) {
632  m_extractorNames.clear();
633  m_extractorNames = extractorNames;
634  m_extractors.clear();
635  initExtractors(m_extractorNames);
636  }
637 
643  inline void setImageFormat(const vpImageFormatType &imageFormat) {
644  m_imageFormat = imageFormat;
645  }
646 
661  inline void setMatcher(const std::string &matcherName) {
662  m_matcherName = matcherName;
663  initMatcher(m_matcherName);
664  }
665 
677  inline void setFilterMatchingType(const vpFilterMatchingType &filterType) {
678  m_filterType = filterType;
679 
680  //Use k-nearest neighbors (knn) to retrieve the two best matches for a keypoint
681  //So this is useful only for ratioDistanceThreshold method
682  if(filterType == ratioDistanceThreshold || filterType == stdAndRatioDistanceThreshold) {
683  m_useKnn = true;
684 
685  #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
686  if(m_matcher != NULL && m_matcherName == "BruteForce") {
687  //if a matcher is already initialized, disable the crossCheck
688  //because it will not work with knnMatch
689  m_matcher->set("crossCheck", false);
690  }
691  #endif
692  } else {
693  m_useKnn = false;
694 
695  #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
696  if(m_matcher != NULL && m_matcherName == "BruteForce") {
697  //if a matcher is already initialized, set the crossCheck mode if necessary
698  m_matcher->set("crossCheck", m_useBruteForceCrossCheck);
699  }
700  #endif
701  }
702  }
703 
709  inline void setMatchingFactorThreshold(const double factor) {
710  if(factor > 0.0) {
711  m_matchingFactorThreshold = factor;
712  } else {
713  throw vpException(vpException::badValue, "The factor must be positive.");
714  }
715  }
716 
722  inline void setMatchingRatioThreshold(const double ratio) {
723  if(ratio > 0.0 && (ratio < 1.0 || std::fabs(ratio - 1.0) < std::numeric_limits<double>::epsilon())) {
724  m_matchingRatioThreshold = ratio;
725  } else {
726  throw vpException(vpException::badValue, "The ratio must be in the interval ]0 ; 1].");
727  }
728  }
729 
735  inline void setRansacConsensusPercentage(const double percentage) {
736  if(percentage > 0.0 && (percentage < 100.0 || std::fabs(percentage - 100.0) < std::numeric_limits<double>::epsilon())) {
737  m_ransacConsensusPercentage = percentage;
738  } else {
739  throw vpException(vpException::badValue, "The percentage must be in the interval ]0 ; 100].");
740  }
741  }
742 
748  inline void setRansacIteration(const int nbIter) {
749  if(nbIter > 0) {
750  m_nbRansacIterations = nbIter;
751  } else {
752  throw vpException(vpException::badValue, "The number of iterations must be greater than zero.");
753  }
754  }
755 
761  inline void setRansacReprojectionError(const double reprojectionError) {
762  if(reprojectionError > 0.0) {
763  m_ransacReprojectionError = reprojectionError;
764  } else {
765  throw vpException(vpException::badValue, "The Ransac reprojection threshold must be positive as we deal with distance.");
766  }
767  }
768 
774  inline void setRansacMinInlierCount(const int minCount) {
775  if(minCount > 0) {
776  m_nbRansacMinInlierCount = minCount;
777  } else {
778  throw vpException(vpException::badValue, "The minimum number of inliers must be greater than zero.");
779  }
780  }
781 
787  inline void setRansacThreshold(const double threshold) {
788  if(threshold > 0.0) {
789  m_ransacThreshold = threshold;
790  } else {
791  throw vpException(vpException::badValue, "The Ransac threshold must be positive as we deal with distance.");
792  }
793  }
794 
800  inline void setUseAffineDetection(const bool useAffine) {
801  m_useAffineDetection = useAffine;
802  }
803 
804 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
805 
810  inline void setUseBruteForceCrossCheck(const bool useCrossCheck) {
811  //Only available with BruteForce and with k=1 (i.e not used with a ratioDistanceThreshold method)
812  if(m_matcher != NULL && !m_useKnn && m_matcherName == "BruteForce") {
813  m_matcher->set("crossCheck", useCrossCheck);
814  } else if(m_matcher != NULL && m_useKnn && m_matcherName == "BruteForce") {
815  std::cout << "Warning, you try to set the crossCheck parameter with a BruteForce matcher but knn is enabled";
816  std::cout << " (the filtering method uses a ratio constraint)" << std::endl;
817  }
818  }
819 #endif
820 
826  inline void setUseMatchTrainToQuery(const bool useMatchTrainToQuery) {
827  m_useMatchTrainToQuery = useMatchTrainToQuery;
828  }
829 
836  inline void setUseRansacConsensusPercentage(const bool usePercentage) {
837  m_useConsensusPercentage = usePercentage;
838  }
839 
845  inline void setUseRansacVVS(const bool ransacVVS) {
846  m_useRansacVVS = ransacVVS;
847  }
848 
854  inline void setUseSingleMatchFilter(const bool singleMatchFilter) {
855  m_useSingleMatchFilter = singleMatchFilter;
856  }
857 
858 private:
860  bool m_computeCovariance;
862  vpMatrix m_covarianceMatrix;
864  int m_currentImageId;
866  vpDetectionMethodType m_detectionMethod;
868  double m_detectionScore;
870  double m_detectionThreshold;
872  double m_detectionTime;
874  std::vector<std::string> m_detectorNames;
876  // with a key based upon the detector name.
877  std::map<std::string, cv::Ptr<cv::FeatureDetector> > m_detectors;
879  double m_extractionTime;
881  std::vector<std::string> m_extractorNames;
883  // with a key based upon the extractor name.
884  std::map<std::string, cv::Ptr<cv::DescriptorExtractor> > m_extractors;
886  std::vector<cv::DMatch> m_filteredMatches;
888  vpFilterMatchingType m_filterType;
890  vpImageFormatType m_imageFormat;
892  std::vector<std::vector<cv::DMatch> > m_knnMatches;
894  std::map<int, int> m_mapOfImageId;
896  std::map<int, vpImage<unsigned char> > m_mapOfImages;
898  cv::Ptr<cv::DescriptorMatcher> m_matcher;
900  std::string m_matcherName;
902  std::vector<cv::DMatch> m_matches;
904  double m_matchingFactorThreshold;
906  double m_matchingRatioThreshold;
908  double m_matchingTime;
910  std::vector<std::pair<cv::KeyPoint, cv::Point3f> > m_matchRansacKeyPointsToPoints;
912  int m_nbRansacIterations;
914  int m_nbRansacMinInlierCount;
916  std::vector<cv::Point3f> m_objectFilteredPoints;
918  double m_poseTime;
921  cv::Mat m_queryDescriptors;
923  std::vector<cv::KeyPoint> m_queryFilteredKeyPoints;
925  std::vector<cv::KeyPoint> m_queryKeyPoints;
927  double m_ransacConsensusPercentage;
929  std::vector<vpImagePoint> m_ransacInliers;
931  std::vector<vpImagePoint> m_ransacOutliers;
933  double m_ransacReprojectionError;
935  double m_ransacThreshold;
937  //detected in the train images).
938  cv::Mat m_trainDescriptors;
940  std::vector<cv::KeyPoint> m_trainKeyPoints;
942  std::vector<cv::Point3f> m_trainPoints;
944  std::vector<vpPoint> m_trainVpPoints;
946  bool m_useAffineDetection;
947 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
948  bool m_useBruteForceCrossCheck;
951 #endif
952  bool m_useConsensusPercentage;
955  bool m_useKnn;
959  bool m_useMatchTrainToQuery;
961  bool m_useRansacVVS;
963  bool m_useSingleMatchFilter;
964 
965 
966  void affineSkew(double tilt, double phi, cv::Mat& img, cv::Mat& mask, cv::Mat& Ai);
967 
968  double computePoseEstimationError(const std::vector<std::pair<cv::KeyPoint, cv::Point3f> > &matchKeyPoints,
969  const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo_est);
970 
971  void filterMatches();
972 
973  void init();
974  void initDetector(const std::string &detectorNames);
975  void initDetectors(const std::vector<std::string> &detectorNames);
976 
977  void initExtractor(const std::string &extractorName);
978  void initExtractors(const std::vector<std::string> &extractorNames);
979 
980  inline size_t myKeypointHash(const cv::KeyPoint &kp) {
981  size_t _Val = 2166136261U, scale = 16777619U;
982  Cv32suf u;
983  u.f = kp.pt.x; _Val = (scale * _Val) ^ u.u;
984  u.f = kp.pt.y; _Val = (scale * _Val) ^ u.u;
985  u.f = kp.size; _Val = (scale * _Val) ^ u.u;
986  //As the keypoint angle can be computed for certain type of keypoint only when extracting
987  //the corresponding descriptor, the angle field is not taking into account for the hash
988 // u.f = kp.angle; _Val = (scale * _Val) ^ u.u;
989  u.f = kp.response; _Val = (scale * _Val) ^ u.u;
990  _Val = (scale * _Val) ^ ((size_t) kp.octave);
991  _Val = (scale * _Val) ^ ((size_t) kp.class_id);
992  return _Val;
993  }
994 
995 
996 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
997  /*
998  * Adapts a detector to detect points over multiple levels of a Gaussian
999  * pyramid. Useful for detectors that are not inherently scaled.
1000  * From OpenCV 2.4.11 source code.
1001  */
1002  class PyramidAdaptedFeatureDetector: public cv::FeatureDetector {
1003  public:
1004  // maxLevel - The 0-based index of the last pyramid layer
1005  PyramidAdaptedFeatureDetector(const cv::Ptr<cv::FeatureDetector>& detector, int maxLevel = 2);
1006 
1007  // TODO implement read/write
1008  virtual bool empty() const;
1009 
1010  protected:
1011  virtual void detect(cv::InputArray image,
1012  CV_OUT std::vector<cv::KeyPoint>& keypoints, cv::InputArray mask =
1013  cv::noArray());
1014  virtual void detectImpl(const cv::Mat& image,
1015  std::vector<cv::KeyPoint>& keypoints, const cv::Mat& mask =
1016  cv::Mat()) const;
1017 
1018  cv::Ptr<cv::FeatureDetector> detector;
1019  int maxLevel;
1020  };
1021 
1022  /*
1023  * A class filters a vector of keypoints.
1024  * Because now it is difficult to provide a convenient interface for all usage scenarios of the keypoints filter class,
1025  * it has only several needed by now static methods.
1026  */
1027  class KeyPointsFilter {
1028  public:
1029  KeyPointsFilter() {
1030  }
1031 
1032  /*
1033  * Remove keypoints within borderPixels of an image edge.
1034  */
1035  static void runByImageBorder(std::vector<cv::KeyPoint>& keypoints,
1036  cv::Size imageSize, int borderSize);
1037  /*
1038  * Remove keypoints of sizes out of range.
1039  */
1040  static void runByKeypointSize(std::vector<cv::KeyPoint>& keypoints,
1041  float minSize, float maxSize = FLT_MAX);
1042  /*
1043  * Remove keypoints from some image by mask for pixels of this image.
1044  */
1045  static void runByPixelsMask(std::vector<cv::KeyPoint>& keypoints,
1046  const cv::Mat& mask);
1047  /*
1048  * Remove duplicated keypoints.
1049  */
1050  static void removeDuplicated(std::vector<cv::KeyPoint>& keypoints);
1051 
1052  /*
1053  * Retain the specified number of the best keypoints (according to the response)
1054  */
1055  static void retainBest(std::vector<cv::KeyPoint>& keypoints, int npoints);
1056  };
1057 
1058 #endif
1059 };
1060 
1061 #endif
1062 #endif
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:92
void setRansacIteration(const int nbIter)
Definition: vpKeyPoint.h:748
class that defines what is a Keypoint. This class provides all the basic elements to implement classe...
void setUseRansacVVS(const bool ransacVVS)
Definition: vpKeyPoint.h:845
Implementation of an homogeneous matrix and operations on such kind of matrices.
std::vector< std::pair< cv::KeyPoint, cv::KeyPoint > > getMatchQueryToTrainKeyPoints() const
Definition: vpKeyPoint.h:422
void setRansacThreshold(const double threshold)
Definition: vpKeyPoint.h:787
void setExtractor(const std::string &extractorName)
Definition: vpKeyPoint.h:603
void setUseSingleMatchFilter(const bool singleMatchFilter)
Definition: vpKeyPoint.h:854
Class to define colors available for display functionnalities.
Definition: vpColor.h:121
error that can be emited by ViSP classes.
Definition: vpException.h:73
void setDetectors(const std::vector< std::string > &detectorNames)
Definition: vpKeyPoint.h:591
static const vpColor green
Definition: vpColor.h:166
Class that defines what is a point.
Definition: vpPoint.h:59
cv::Mat getQueryDescriptors() const
Definition: vpKeyPoint.h:458
void setExtractors(const std::vector< std::string > &extractorNames)
Definition: vpKeyPoint.h:631
void setMatcher(const std::string &matcherName)
Definition: vpKeyPoint.h:661
void setUseMatchTrainToQuery(const bool useMatchTrainToQuery)
Definition: vpKeyPoint.h:826
cv::Ptr< cv::DescriptorMatcher > getMatcher() const
Definition: vpKeyPoint.h:404
virtual unsigned int buildReference(const vpImage< unsigned char > &I)=0
double getDetectionTime() const
Definition: vpKeyPoint.h:338
Generic class defining intrinsic camera parameters.
double getMatchingTime() const
Definition: vpKeyPoint.h:395
void setDetectionMethod(const vpDetectionMethodType &method)
Definition: vpKeyPoint.h:554
void setUseBruteForceCrossCheck(const bool useCrossCheck)
Definition: vpKeyPoint.h:810
unsigned int getNbImages() const
Definition: vpKeyPoint.h:437
cv::Ptr< cv::FeatureDetector > getDetector(const std::string &name) const
Definition: vpKeyPoint.h:348
void setRansacMinInlierCount(const int minCount)
Definition: vpKeyPoint.h:774
vpMatrix getCovarianceMatrix() const
Definition: vpKeyPoint.h:317
void setImageFormat(const vpImageFormatType &imageFormat)
Definition: vpKeyPoint.h:643
virtual void display(const vpImage< unsigned char > &Iref, const vpImage< unsigned char > &Icurrent, unsigned int size=3)=0
void setRansacConsensusPercentage(const double percentage)
Definition: vpKeyPoint.h:735
virtual unsigned int matchPoint(const vpImage< unsigned char > &I)=0
vpImageFormatType getImageFormat() const
Definition: vpKeyPoint.h:386
void setUseAffineDetection(const bool useAffine)
Definition: vpKeyPoint.h:800
Class that allows keypoints detection (and descriptors extraction) and matching thanks to OpenCV libr...
Definition: vpKeyPoint.h:213
std::vector< vpImagePoint > getRansacOutliers() const
Definition: vpKeyPoint.h:479
vpDetectionMethodType
Definition: vpKeyPoint.h:227
void setDetectorParameter(const T1 detectorName, const T2 parameterName, const T3 value)
Definition: vpKeyPoint.h:578
vpFilterMatchingType
Definition: vpKeyPoint.h:218
cv::Mat getTrainDescriptors() const
Definition: vpKeyPoint.h:488
double getExtractionTime() const
Definition: vpKeyPoint.h:362
double getPoseTime() const
Definition: vpKeyPoint.h:449
void setDetector(const std::string &detectorName)
Definition: vpKeyPoint.h:563
Defines a rectangle in the plane.
Definition: vpRect.h:81
cv::Ptr< cv::DescriptorExtractor > getExtractor(const std::string &name) const
Definition: vpKeyPoint.h:372
void setExtractorParameter(const T1 extractorName, const T2 parameterName, const T3 value)
Definition: vpKeyPoint.h:618
void setUseRansacConsensusPercentage(const bool usePercentage)
Definition: vpKeyPoint.h:836
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:88
std::vector< vpImagePoint > getRansacInliers() const
Definition: vpKeyPoint.h:470
void setFilterMatchingType(const vpFilterMatchingType &filterType)
Definition: vpKeyPoint.h:677
void setMatchingFactorThreshold(const double factor)
Definition: vpKeyPoint.h:709
std::vector< cv::DMatch > getMatches() const
Definition: vpKeyPoint.h:413
void setRansacReprojectionError(const double reprojectionError)
Definition: vpKeyPoint.h:761
void setMatchingRatioThreshold(const double ratio)
Definition: vpKeyPoint.h:722
void setCovarianceComputation(const bool &flag)
Definition: vpKeyPoint.h:540