37 #ifndef __vpKeyPoint_h__
38 #define __vpKeyPoint_h__
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>
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 #include <visp3/core/vpCylinder.h>
68 #if (VISP_HAVE_OPENCV_VERSION >= 0x020101)
70 #include <opencv2/features2d/features2d.hpp>
71 #include <opencv2/calib3d/calib3d.hpp>
72 #include <opencv2/imgproc/imgproc.hpp>
74 #if defined(VISP_HAVE_OPENCV_XFEATURES2D) // OpenCV >= 3.0.0
75 # include <opencv2/xfeatures2d.hpp>
76 #elif defined(VISP_HAVE_OPENCV_NONFREE) && (VISP_HAVE_OPENCV_VERSION >= 0x020400) && (VISP_HAVE_OPENCV_VERSION < 0x030000)
77 # include <opencv2/nonfree/nonfree.hpp>
81 # include <libxml/xmlwriter.h>
247 #if (VISP_HAVE_OPENCV_VERSION >= 0x020403)
254 #if (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined (VISP_HAVE_OPENCV_XFEATURES2D))
257 #if defined(VISP_HAVE_OPENCV_NONFREE) || defined (VISP_HAVE_OPENCV_XFEATURES2D)
261 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
266 #if (VISP_HAVE_OPENCV_VERSION >= 0x030100) && defined (VISP_HAVE_OPENCV_XFEATURES2D)
275 #if (VISP_HAVE_OPENCV_VERSION >= 0x020403)
278 #if (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined (VISP_HAVE_OPENCV_XFEATURES2D))
282 #if defined(VISP_HAVE_OPENCV_NONFREE) || defined (VISP_HAVE_OPENCV_XFEATURES2D)
286 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
289 #if defined (VISP_HAVE_OPENCV_XFEATURES2D)
294 #if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined (VISP_HAVE_OPENCV_XFEATURES2D)
296 DESCRIPTOR_BoostDesc,
303 vpKeyPoint(
const vpFeatureDetectorType &detectorType,
const vpFeatureDescriptorType &descriptorType,
304 const std::string &matcherName,
const vpFilterMatchingType &filterType=ratioDistanceThreshold);
305 vpKeyPoint(
const std::string &detectorName=
"ORB",
const std::string &extractorName=
"ORB",
306 const std::string &matcherName=
"BruteForce-Hamming",
const vpFilterMatchingType &filterType=ratioDistanceThreshold);
307 vpKeyPoint(
const std::vector<std::string> &detectorNames,
const std::vector<std::string> &extractorNames,
308 const std::string &matcherName=
"BruteForce",
const vpFilterMatchingType &filterType=ratioDistanceThreshold);
312 const vpImagePoint &iP,
const unsigned int height,
const unsigned int width);
316 std::vector<cv::Point3f> &points3f,
const bool append=
false,
const int class_id=-1);
318 const cv::Mat &trainDescriptors,
const std::vector<cv::Point3f> &points3f,
319 const bool append=
false,
const int class_id=-1);
321 static void compute3D(
const cv::KeyPoint &candidate,
const std::vector<vpPoint> &roi,
324 static void compute3D(
const vpImagePoint &candidate,
const std::vector<vpPoint> &roi,
328 std::vector<cv::KeyPoint> &candidates,
const std::vector<vpPolygon> &polygons,
329 const std::vector<std::vector<vpPoint> > &roisPt, std::vector<cv::Point3f> &points, cv::Mat *descriptors=NULL);
332 std::vector<vpImagePoint> &candidates,
const std::vector<vpPolygon> &polygons,
333 const std::vector<std::vector<vpPoint> > &roisPt, std::vector<vpPoint> &points, cv::Mat *descriptors=NULL);
336 std::vector<cv::KeyPoint> &candidates,
const std::vector<vpCylinder> &cylinders,
337 const std::vector<std::vector<std::vector<vpImagePoint> > > &vectorOfCylinderRois,
338 std::vector<cv::Point3f> &points, cv::Mat *descriptors=NULL);
341 std::vector<vpImagePoint> &candidates,
const std::vector<vpCylinder> &cylinders,
342 const std::vector<std::vector<std::vector<vpImagePoint> > > &vectorOfCylinderRois,
343 std::vector<vpPoint> &points, cv::Mat *descriptors=NULL);
345 bool computePose(
const std::vector<cv::Point2f> &imagePoints,
const std::vector<cv::Point3f> &objectPoints,
350 std::vector<vpPoint> &inliers,
double &elapsedTime,
bool (*func)(
vpHomogeneousMatrix *)=NULL);
353 std::vector<vpPoint> &inliers, std::vector<unsigned int> &inlierIndex,
360 void detect(
const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints,
const cv::Mat &mask=cv::Mat());
363 void detect(
const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints,
double &elapsedTime,
364 const cv::Mat &mask=cv::Mat());
366 void detectExtractAffine(
const vpImage<unsigned char> &I, std::vector<std::vector<cv::KeyPoint> >& listOfKeypoints,
367 std::vector<cv::Mat>& listOfDescriptors,
374 unsigned int crossSize,
unsigned int lineThickness=1,
377 const std::vector<vpImagePoint> &ransacInliers=std::vector<vpImagePoint>(),
unsigned int crossSize=3,
378 unsigned int lineThickness=1);
380 void extract(
const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors, std::vector<cv::Point3f> *trainPoints=NULL);
381 void extract(
const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors, std::vector<cv::Point3f> *trainPoints=NULL);
383 double &elapsedTime, std::vector<cv::Point3f> *trainPoints=NULL);
384 void extract(
const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
385 double &elapsedTime, std::vector<cv::Point3f> *trainPoints=NULL);
395 if(!m_computeCovariance) {
396 std::cout <<
"Warning : The covariance matrix has not been computed. See setCovarianceComputation() to do it." << std::endl;
400 if(m_computeCovariance && !m_useRansacVVS) {
401 std::cout <<
"Warning : The covariance matrix can only be computed with a Virtual Visual Servoing approach." << std::endl
402 <<
"Use setUseRansacVVS(true) to choose to use a pose estimation method based on a Virtual Visual Servoing approach."
407 return m_covarianceMatrix;
416 return m_detectionTime;
426 std::map<vpFeatureDetectorType, std::string>::const_iterator it_name = m_mapOfDetectorNames.find(type);
427 if (it_name == m_mapOfDetectorNames.end()) {
428 std::cerr <<
"Internal problem with the feature type and the corresponding name!" << std::endl;
431 std::map<std::string, cv::Ptr<cv::FeatureDetector> >::const_iterator findDetector = m_detectors.find(it_name->second);
432 if(findDetector != m_detectors.end()) {
433 return findDetector->second;
436 std::cerr <<
"Cannot find: " << it_name->second << std::endl;
437 return cv::Ptr<cv::FeatureDetector>();
446 inline cv::Ptr<cv::FeatureDetector>
getDetector(
const std::string &name)
const {
447 std::map<std::string, cv::Ptr<cv::FeatureDetector> >::const_iterator findDetector = m_detectors.find(name);
448 if(findDetector != m_detectors.end()) {
449 return findDetector->second;
452 std::cerr <<
"Cannot find: " << name << std::endl;
453 return cv::Ptr<cv::FeatureDetector>();
460 return m_mapOfDetectorNames;
469 return m_extractionTime;
479 std::map<vpFeatureDescriptorType, std::string>::const_iterator it_name = m_mapOfDescriptorNames.find(type);
480 if (it_name == m_mapOfDescriptorNames.end()) {
481 std::cerr <<
"Internal problem with the feature type and the corresponding name!" << std::endl;
484 std::map<std::string, cv::Ptr<cv::DescriptorExtractor> >::const_iterator findExtractor = m_extractors.find(it_name->second);
485 if(findExtractor != m_extractors.end()) {
486 return findExtractor->second;
489 std::cerr <<
"Cannot find: " << it_name->second << std::endl;
490 return cv::Ptr<cv::DescriptorExtractor>();
499 inline cv::Ptr<cv::DescriptorExtractor>
getExtractor(
const std::string &name)
const {
500 std::map<std::string, cv::Ptr<cv::DescriptorExtractor> >::const_iterator findExtractor = m_extractors.find(name);
501 if(findExtractor != m_extractors.end()) {
502 return findExtractor->second;
505 std::cerr <<
"Cannot find: " << name << std::endl;
506 return cv::Ptr<cv::DescriptorExtractor>();
513 return m_mapOfDescriptorNames;
522 return m_imageFormat;
531 return m_matchingTime;
549 return m_filteredMatches;
558 std::vector<std::pair<cv::KeyPoint, cv::KeyPoint> > matchQueryToTrainKeyPoints(m_filteredMatches.size());
559 for (
size_t i = 0; i < m_filteredMatches.size(); i++) {
560 matchQueryToTrainKeyPoints.push_back(std::pair<cv::KeyPoint, cv::KeyPoint>(
561 m_queryFilteredKeyPoints[(
size_t) m_filteredMatches[i].queryIdx],
562 m_trainKeyPoints[(
size_t) m_filteredMatches[i].trainIdx]));
564 return matchQueryToTrainKeyPoints;
573 return static_cast<unsigned int>(m_mapOfImages.size());
576 void getObjectPoints(std::vector<cv::Point3f> &objectPoints)
const;
577 void getObjectPoints(std::vector<vpPoint> &objectPoints)
const;
594 return m_queryDescriptors;
597 void getQueryKeyPoints(std::vector<cv::KeyPoint> &keyPoints)
const;
598 void getQueryKeyPoints(std::vector<vpImagePoint> &keyPoints)
const;
606 return m_ransacInliers;
615 return m_ransacOutliers;
624 return m_trainDescriptors;
627 void getTrainKeyPoints(std::vector<cv::KeyPoint> &keyPoints)
const;
628 void getTrainKeyPoints(std::vector<vpImagePoint> &keyPoints)
const;
630 void getTrainPoints(std::vector<cv::Point3f> &points)
const;
631 void getTrainPoints(std::vector<vpPoint> &points)
const;
633 void initMatcher(
const std::string &matcherName);
639 #ifdef VISP_HAVE_XML2
640 void loadConfigFile(
const std::string &configFile);
643 void loadLearningData(
const std::string &filename,
const bool binaryMode=
false,
const bool append=
false);
645 void match(
const cv::Mat &trainDescriptors,
const cv::Mat &queryDescriptors,
646 std::vector<cv::DMatch> &matches,
double &elapsedTime);
650 const unsigned int height,
const unsigned int width);
660 const bool isPlanarObject=
true, std::vector<vpImagePoint> *imPts1=NULL,
661 std::vector<vpImagePoint> *imPts2=NULL,
double *meanDescriptorDistance=NULL,
662 double *detectionScore=NULL,
const vpRect& rectangle=
vpRect());
665 double &error,
double &elapsedTime,
vpRect &boundingBox,
vpImagePoint ¢erOfGravity,
670 void saveLearningData(
const std::string &filename,
const bool binaryMode=
false,
const bool saveTrainingImages=
true);
678 m_computeCovariance = flag;
679 if(!m_useRansacVVS) {
680 std::cout <<
"Warning : The covariance matrix can only be computed with a Virtual Visual Servoing approach." << std::endl
681 <<
"Use setUseRansacVVS(true) to choose to use a pose estimation method based on a Virtual "
682 "Visual Servoing approach." << std::endl;
692 m_detectionMethod = method;
701 m_detectorNames.clear();
702 m_detectorNames.push_back(m_mapOfDetectorNames[detectorType]);
704 initDetector(m_mapOfDetectorNames[detectorType]);
713 m_detectorNames.clear();
714 m_detectorNames.push_back(detectorName);
716 initDetector(detectorName);
719 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
728 const T2 parameterName,
const T3 value) {
729 if(m_detectors.find(detectorName) != m_detectors.end()) {
730 m_detectors[detectorName]->set(parameterName, value);
740 inline void setDetectors(
const std::vector<std::string> &detectorNames) {
741 m_detectorNames.clear();
743 m_detectorNames = detectorNames;
744 initDetectors(m_detectorNames);
753 m_extractorNames.clear();
754 m_extractorNames.push_back(m_mapOfDescriptorNames[extractorType]);
755 m_extractors.clear();
756 initExtractor(m_mapOfDescriptorNames[extractorType]);
765 m_extractorNames.clear();
766 m_extractorNames.push_back(extractorName);
767 m_extractors.clear();
768 initExtractor(extractorName);
771 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
780 const T2 parameterName,
const T3 value) {
781 if(m_extractors.find(extractorName) != m_extractors.end()) {
782 m_extractors[extractorName]->set(parameterName, value);
793 m_extractorNames.clear();
794 m_extractorNames = extractorNames;
795 m_extractors.clear();
796 initExtractors(m_extractorNames);
805 m_imageFormat = imageFormat;
823 m_matcherName = matcherName;
824 initMatcher(m_matcherName);
839 m_filterType = filterType;
843 if(filterType == ratioDistanceThreshold || filterType == stdAndRatioDistanceThreshold) {
846 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
847 if(m_matcher != NULL && m_matcherName ==
"BruteForce") {
850 m_matcher->set(
"crossCheck",
false);
856 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
857 if(m_matcher != NULL && m_matcherName ==
"BruteForce") {
859 m_matcher->set(
"crossCheck", m_useBruteForceCrossCheck);
872 m_matchingFactorThreshold = factor;
884 if(ratio > 0.0 && (ratio < 1.0 || std::fabs(ratio - 1.0) < std::numeric_limits<double>::epsilon())) {
885 m_matchingRatioThreshold = ratio;
897 if(percentage > 0.0 && (percentage < 100.0 || std::fabs(percentage - 100.0) < std::numeric_limits<double>::epsilon())) {
898 m_ransacConsensusPercentage = percentage;
911 m_nbRansacIterations = nbIter;
923 if(reprojectionError > 0.0) {
924 m_ransacReprojectionError = reprojectionError;
937 m_nbRansacMinInlierCount = minCount;
949 if(threshold > 0.0) {
950 m_ransacThreshold = threshold;
962 m_useAffineDetection = useAffine;
965 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
973 if(m_matcher != NULL && !m_useKnn && m_matcherName ==
"BruteForce") {
974 m_matcher->set(
"crossCheck", useCrossCheck);
975 }
else if(m_matcher != NULL && m_useKnn && m_matcherName ==
"BruteForce") {
976 std::cout <<
"Warning, you try to set the crossCheck parameter with a BruteForce matcher but knn is enabled";
977 std::cout <<
" (the filtering method uses a ratio constraint)" << std::endl;
988 m_useMatchTrainToQuery = useMatchTrainToQuery;
998 m_useConsensusPercentage = usePercentage;
1007 m_useRansacVVS = ransacVVS;
1016 m_useSingleMatchFilter = singleMatchFilter;
1021 bool m_computeCovariance;
1025 int m_currentImageId;
1027 vpDetectionMethodType m_detectionMethod;
1029 double m_detectionScore;
1031 double m_detectionThreshold;
1033 double m_detectionTime;
1035 std::vector<std::string> m_detectorNames;
1038 std::map<std::string, cv::Ptr<cv::FeatureDetector> > m_detectors;
1040 double m_extractionTime;
1042 std::vector<std::string> m_extractorNames;
1045 std::map<std::string, cv::Ptr<cv::DescriptorExtractor> > m_extractors;
1047 std::vector<cv::DMatch> m_filteredMatches;
1049 vpFilterMatchingType m_filterType;
1051 vpImageFormatType m_imageFormat;
1053 std::vector<std::vector<cv::DMatch> > m_knnMatches;
1055 std::map<vpFeatureDescriptorType, std::string> m_mapOfDescriptorNames;
1057 std::map<vpFeatureDetectorType, std::string> m_mapOfDetectorNames;
1059 std::map<int, int> m_mapOfImageId;
1061 std::map<int, vpImage<unsigned char> > m_mapOfImages;
1063 cv::Ptr<cv::DescriptorMatcher> m_matcher;
1065 std::string m_matcherName;
1067 std::vector<cv::DMatch> m_matches;
1069 double m_matchingFactorThreshold;
1071 double m_matchingRatioThreshold;
1073 double m_matchingTime;
1075 std::vector<std::pair<cv::KeyPoint, cv::Point3f> > m_matchRansacKeyPointsToPoints;
1077 int m_nbRansacIterations;
1079 int m_nbRansacMinInlierCount;
1081 std::vector<cv::Point3f> m_objectFilteredPoints;
1086 cv::Mat m_queryDescriptors;
1088 std::vector<cv::KeyPoint> m_queryFilteredKeyPoints;
1090 std::vector<cv::KeyPoint> m_queryKeyPoints;
1092 double m_ransacConsensusPercentage;
1094 std::vector<vpImagePoint> m_ransacInliers;
1096 std::vector<vpImagePoint> m_ransacOutliers;
1098 double m_ransacReprojectionError;
1100 double m_ransacThreshold;
1103 cv::Mat m_trainDescriptors;
1105 std::vector<cv::KeyPoint> m_trainKeyPoints;
1107 std::vector<cv::Point3f> m_trainPoints;
1109 std::vector<vpPoint> m_trainVpPoints;
1111 bool m_useAffineDetection;
1112 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
1113 bool m_useBruteForceCrossCheck;
1117 bool m_useConsensusPercentage;
1124 bool m_useMatchTrainToQuery;
1126 bool m_useRansacVVS;
1128 bool m_useSingleMatchFilter;
1131 void affineSkew(
double tilt,
double phi, cv::Mat& img, cv::Mat& mask, cv::Mat& Ai);
1133 double computePoseEstimationError(
const std::vector<std::pair<cv::KeyPoint, cv::Point3f> > &matchKeyPoints,
1136 void filterMatches();
1139 void initDetector(
const std::string &detectorNames);
1140 void initDetectors(
const std::vector<std::string> &detectorNames);
1142 void initExtractor(
const std::string &extractorName);
1143 void initExtractors(
const std::vector<std::string> &extractorNames);
1145 void initFeatureNames();
1147 inline size_t myKeypointHash(
const cv::KeyPoint &kp) {
1148 size_t _Val = 2166136261U, scale = 16777619U;
1150 u.f = kp.pt.x; _Val = (scale * _Val) ^ u.u;
1151 u.f = kp.pt.y; _Val = (scale * _Val) ^ u.u;
1152 u.f = kp.size; _Val = (scale * _Val) ^ u.u;
1156 u.f = kp.response; _Val = (scale * _Val) ^ u.u;
1157 _Val = (scale * _Val) ^ ((
size_t) kp.octave);
1158 _Val = (scale * _Val) ^ ((
size_t) kp.class_id);
1163 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
1169 class PyramidAdaptedFeatureDetector:
public cv::FeatureDetector {
1172 PyramidAdaptedFeatureDetector(
const cv::Ptr<cv::FeatureDetector>& detector,
int maxLevel = 2);
1175 virtual bool empty()
const;
1178 virtual void detect(cv::InputArray image,
1179 CV_OUT std::vector<cv::KeyPoint>& keypoints, cv::InputArray mask =
1181 virtual void detectImpl(
const cv::Mat& image,
1182 std::vector<cv::KeyPoint>& keypoints,
const cv::Mat& mask =
1185 cv::Ptr<cv::FeatureDetector> detector;
1194 class KeyPointsFilter {
1202 static void runByImageBorder(std::vector<cv::KeyPoint>& keypoints,
1203 cv::Size imageSize,
int borderSize);
1207 static void runByKeypointSize(std::vector<cv::KeyPoint>& keypoints,
1208 float minSize,
float maxSize = FLT_MAX);
1212 static void runByPixelsMask(std::vector<cv::KeyPoint>& keypoints,
1213 const cv::Mat& mask);
1217 static void removeDuplicated(std::vector<cv::KeyPoint>& keypoints);
1222 static void retainBest(std::vector<cv::KeyPoint>& keypoints,
int npoints);
Implementation of a matrix and operations on matrices.
void setRansacIteration(const int nbIter)
class that defines what is a Keypoint. This class provides all the basic elements to implement classe...
void setUseRansacVVS(const bool ransacVVS)
Implementation of an homogeneous matrix and operations on such kind of matrices.
std::vector< std::pair< cv::KeyPoint, cv::KeyPoint > > getMatchQueryToTrainKeyPoints() const
void setRansacThreshold(const double threshold)
void setExtractor(const std::string &extractorName)
void setUseSingleMatchFilter(const bool singleMatchFilter)
Class to define colors available for display functionnalities.
std::map< vpFeatureDetectorType, std::string > getDetectorNames() const
error that can be emited by ViSP classes.
void setDetectors(const std::vector< std::string > &detectorNames)
static const vpColor green
cv::Ptr< cv::DescriptorExtractor > getExtractor(const vpFeatureDescriptorType &type) const
Class that defines what is a point.
cv::Mat getQueryDescriptors() const
void setExtractors(const std::vector< std::string > &extractorNames)
void setMatcher(const std::string &matcherName)
void setUseMatchTrainToQuery(const bool useMatchTrainToQuery)
cv::Ptr< cv::DescriptorMatcher > getMatcher() const
virtual unsigned int buildReference(const vpImage< unsigned char > &I)=0
double getDetectionTime() const
Generic class defining intrinsic camera parameters.
void setDetector(const vpFeatureDetectorType &detectorType)
double getMatchingTime() const
void setDetectionMethod(const vpDetectionMethodType &method)
void setUseBruteForceCrossCheck(const bool useCrossCheck)
unsigned int getNbImages() const
cv::Ptr< cv::FeatureDetector > getDetector(const std::string &name) const
void setRansacMinInlierCount(const int minCount)
vpMatrix getCovarianceMatrix() const
void setImageFormat(const vpImageFormatType &imageFormat)
virtual void display(const vpImage< unsigned char > &Iref, const vpImage< unsigned char > &Icurrent, unsigned int size=3)=0
void setRansacConsensusPercentage(const double percentage)
virtual unsigned int matchPoint(const vpImage< unsigned char > &I)=0
vpImageFormatType getImageFormat() const
void setUseAffineDetection(const bool useAffine)
std::map< vpFeatureDescriptorType, std::string > getExtractorNames() const
Class that allows keypoints detection (and descriptors extraction) and matching thanks to OpenCV libr...
std::vector< vpImagePoint > getRansacOutliers() const
void setDetectorParameter(const T1 detectorName, const T2 parameterName, const T3 value)
cv::Mat getTrainDescriptors() const
double getExtractionTime() const
double getPoseTime() const
void setDetector(const std::string &detectorName)
Defines a rectangle in the plane.
cv::Ptr< cv::DescriptorExtractor > getExtractor(const std::string &name) const
void setExtractorParameter(const T1 extractorName, const T2 parameterName, const T3 value)
void setUseRansacConsensusPercentage(const bool usePercentage)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
std::vector< vpImagePoint > getRansacInliers() const
void setFilterMatchingType(const vpFilterMatchingType &filterType)
void setMatchingFactorThreshold(const double factor)
cv::Ptr< cv::FeatureDetector > getDetector(const vpFeatureDetectorType &type) const
void setExtractor(const vpFeatureDescriptorType &extractorType)
std::vector< cv::DMatch > getMatches() const
void setRansacReprojectionError(const double reprojectionError)
void setMatchingRatioThreshold(const double ratio)
void setCovarianceComputation(const bool &flag)