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>
67 #if (VISP_HAVE_OPENCV_VERSION >= 0x020101)
69 #include <opencv2/features2d/features2d.hpp>
70 #include <opencv2/calib3d/calib3d.hpp>
71 #include <opencv2/imgproc/imgproc.hpp>
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>
80 # include <libxml/xmlwriter.h>
224 } vpFilterMatchingType;
231 } vpDetectionMethodType;
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);
249 const vpImagePoint &iP,
const unsigned int height,
const unsigned int width);
253 std::vector<cv::Point3f> &points3f,
const bool append=
false,
const int class_id=-1);
255 const cv::Mat &trainDescriptors,
const std::vector<cv::Point3f> &points3f,
256 const bool append=
false,
const int class_id=-1);
258 static void compute3D(
const cv::KeyPoint &candidate,
const std::vector<vpPoint> &roi,
261 static void compute3D(
const vpImagePoint &candidate,
const std::vector<vpPoint> &roi,
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);
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);
272 bool computePose(
const std::vector<cv::Point2f> &imagePoints,
const std::vector<cv::Point3f> &objectPoints,
277 std::vector<vpPoint> &inliers,
double &elapsedTime,
bool (*func)(
vpHomogeneousMatrix *)=NULL);
280 std::vector<vpPoint> &inliers, std::vector<unsigned int> &inlierIndex,
288 void detect(
const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints,
double &elapsedTime,
289 const cv::Mat &mask=cv::Mat());
291 void detectExtractAffine(
const vpImage<unsigned char> &I, std::vector<std::vector<cv::KeyPoint> >& listOfKeypoints,
292 std::vector<cv::Mat>& listOfDescriptors,
299 unsigned int crossSize,
unsigned int lineThickness=1,
302 const std::vector<vpImagePoint> &ransacInliers=std::vector<vpImagePoint>(),
unsigned int crossSize=3,
303 unsigned int lineThickness=1);
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);
318 if(!m_computeCovariance) {
319 std::cout <<
"Warning : The covariance matrix has not been computed. See setCovarianceComputation() to do it." << std::endl;
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."
330 return m_covarianceMatrix;
339 return m_detectionTime;
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;
354 return cv::Ptr<cv::FeatureDetector>();
363 return m_extractionTime;
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;
378 return cv::Ptr<cv::DescriptorExtractor>();
387 return m_imageFormat;
396 return m_matchingTime;
414 return m_filteredMatches;
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]));
429 return matchQueryToTrainKeyPoints;
438 return static_cast<unsigned int>(m_mapOfImages.size());
441 void getObjectPoints(std::vector<cv::Point3f> &objectPoints)
const;
442 void getObjectPoints(std::vector<vpPoint> &objectPoints)
const;
459 return m_queryDescriptors;
462 void getQueryKeyPoints(std::vector<cv::KeyPoint> &keyPoints)
const;
463 void getQueryKeyPoints(std::vector<vpImagePoint> &keyPoints)
const;
471 return m_ransacInliers;
480 return m_ransacOutliers;
489 return m_trainDescriptors;
492 void getTrainKeyPoints(std::vector<cv::KeyPoint> &keyPoints)
const;
493 void getTrainKeyPoints(std::vector<vpImagePoint> &keyPoints)
const;
495 void getTrainPoints(std::vector<cv::Point3f> &points)
const;
496 void getTrainPoints(std::vector<vpPoint> &points)
const;
498 void initMatcher(
const std::string &matcherName);
504 #ifdef VISP_HAVE_XML2
505 void loadConfigFile(
const std::string &configFile);
508 void loadLearningData(
const std::string &filename,
const bool binaryMode=
false,
const bool append=
false);
510 void match(
const cv::Mat &trainDescriptors,
const cv::Mat &queryDescriptors,
511 std::vector<cv::DMatch> &matches,
double &elapsedTime);
515 const unsigned int height,
const unsigned int width);
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());
528 double &error,
double &elapsedTime,
vpRect &boundingBox,
vpImagePoint ¢erOfGravity,
533 void saveLearningData(
const std::string &filename,
const bool binaryMode=
false,
const bool saveTrainingImages=
true);
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;
555 m_detectionMethod = method;
564 m_detectorNames.clear();
565 m_detectorNames.push_back(detectorName);
567 initDetector(detectorName);
570 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
579 const T2 parameterName,
const T3 value) {
580 if(m_detectors.find(detectorName) != m_detectors.end()) {
581 m_detectors[detectorName]->set(parameterName, value);
591 inline void setDetectors(
const std::vector<std::string> &detectorNames) {
592 m_detectorNames.clear();
594 m_detectorNames = detectorNames;
595 initDetectors(m_detectorNames);
604 m_extractorNames.clear();
605 m_extractorNames.push_back(extractorName);
606 m_extractors.clear();
607 initExtractor(extractorName);
610 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
619 const T2 parameterName,
const T3 value) {
620 if(m_extractors.find(extractorName) != m_extractors.end()) {
621 m_extractors[extractorName]->set(parameterName, value);
632 m_extractorNames.clear();
633 m_extractorNames = extractorNames;
634 m_extractors.clear();
635 initExtractors(m_extractorNames);
644 m_imageFormat = imageFormat;
662 m_matcherName = matcherName;
663 initMatcher(m_matcherName);
678 m_filterType = filterType;
682 if(filterType == ratioDistanceThreshold || filterType == stdAndRatioDistanceThreshold) {
685 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
686 if(m_matcher != NULL && m_matcherName ==
"BruteForce") {
689 m_matcher->set(
"crossCheck",
false);
695 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
696 if(m_matcher != NULL && m_matcherName ==
"BruteForce") {
698 m_matcher->set(
"crossCheck", m_useBruteForceCrossCheck);
711 m_matchingFactorThreshold = factor;
723 if(ratio > 0.0 && (ratio < 1.0 || std::fabs(ratio - 1.0) < std::numeric_limits<double>::epsilon())) {
724 m_matchingRatioThreshold = ratio;
736 if(percentage > 0.0 && (percentage < 100.0 || std::fabs(percentage - 100.0) < std::numeric_limits<double>::epsilon())) {
737 m_ransacConsensusPercentage = percentage;
750 m_nbRansacIterations = nbIter;
762 if(reprojectionError > 0.0) {
763 m_ransacReprojectionError = reprojectionError;
776 m_nbRansacMinInlierCount = minCount;
788 if(threshold > 0.0) {
789 m_ransacThreshold = threshold;
801 m_useAffineDetection = useAffine;
804 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
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;
827 m_useMatchTrainToQuery = useMatchTrainToQuery;
837 m_useConsensusPercentage = usePercentage;
846 m_useRansacVVS = ransacVVS;
855 m_useSingleMatchFilter = singleMatchFilter;
860 bool m_computeCovariance;
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;
877 std::map<std::string, cv::Ptr<cv::FeatureDetector> > m_detectors;
879 double m_extractionTime;
881 std::vector<std::string> m_extractorNames;
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;
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;
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;
952 bool m_useConsensusPercentage;
959 bool m_useMatchTrainToQuery;
963 bool m_useSingleMatchFilter;
966 void affineSkew(
double tilt,
double phi, cv::Mat& img, cv::Mat& mask, cv::Mat& Ai);
968 double computePoseEstimationError(
const std::vector<std::pair<cv::KeyPoint, cv::Point3f> > &matchKeyPoints,
971 void filterMatches();
974 void initDetector(
const std::string &detectorNames);
975 void initDetectors(
const std::vector<std::string> &detectorNames);
977 void initExtractor(
const std::string &extractorName);
978 void initExtractors(
const std::vector<std::string> &extractorNames);
980 inline size_t myKeypointHash(
const cv::KeyPoint &kp) {
981 size_t _Val = 2166136261U, scale = 16777619U;
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;
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);
996 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
1002 class PyramidAdaptedFeatureDetector:
public cv::FeatureDetector {
1005 PyramidAdaptedFeatureDetector(
const cv::Ptr<cv::FeatureDetector>& detector,
int maxLevel = 2);
1008 virtual bool empty()
const;
1011 virtual void detect(cv::InputArray image,
1012 CV_OUT std::vector<cv::KeyPoint>& keypoints, cv::InputArray mask =
1014 virtual void detectImpl(
const cv::Mat& image,
1015 std::vector<cv::KeyPoint>& keypoints,
const cv::Mat& mask =
1018 cv::Ptr<cv::FeatureDetector> detector;
1027 class KeyPointsFilter {
1035 static void runByImageBorder(std::vector<cv::KeyPoint>& keypoints,
1036 cv::Size imageSize,
int borderSize);
1040 static void runByKeypointSize(std::vector<cv::KeyPoint>& keypoints,
1041 float minSize,
float maxSize = FLT_MAX);
1045 static void runByPixelsMask(std::vector<cv::KeyPoint>& keypoints,
1046 const cv::Mat& mask);
1050 static void removeDuplicated(std::vector<cv::KeyPoint>& keypoints);
1055 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.
error that can be emited by ViSP classes.
void setDetectors(const std::vector< std::string > &detectorNames)
static const vpColor green
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.
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)
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)
std::vector< cv::DMatch > getMatches() const
void setRansacReprojectionError(const double reprojectionError)
void setMatchingRatioThreshold(const double ratio)
void setCovarianceComputation(const bool &flag)