Visual Servoing Platform  version 3.6.1 under development (2025-02-01)
vpKeyPoint.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
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 https://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 
34 #include <visp3/core/vpConfig.h>
35 
36 // opencv_xfeatures2d and opencv_nonfree are optional
37 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_CALIB3D) && defined(HAVE_OPENCV_FEATURES2D)) || \
38  ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_3D) && defined(HAVE_OPENCV_FEATURES))
39 
40 #include <iomanip>
41 #include <limits>
42 
43 #include <visp3/core/vpIoTools.h>
44 #include <visp3/vision/vpKeyPoint.h>
45 
46 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
47 #include <opencv2/3d.hpp>
48 #include <opencv2/features.hpp>
49 #endif
50 
51 #if (VISP_HAVE_OPENCV_VERSION <0x050000)
52 #include <opencv2/calib3d/calib3d.hpp>
53 #endif
54 
55 #if defined(HAVE_OPENCV_XFEATURES2D)
56 #include <opencv2/xfeatures2d.hpp>
57 #endif
58 
59 #if defined(VISP_HAVE_PUGIXML)
60 #include <pugixml.hpp>
61 #endif
62 
63 BEGIN_VISP_NAMESPACE
64 
65 #ifndef DOXYGEN_SHOULD_SKIP_THIS
66 namespace
67 {
68 // Specific Type transformation functions
69 inline cv::DMatch knnToDMatch(const std::vector<cv::DMatch> &knnMatches)
70 {
71  if (knnMatches.size() > 0) {
72  return knnMatches[0];
73  }
74 
75  return cv::DMatch();
76 }
77 
78 inline vpImagePoint matchRansacToVpImage(const std::pair<cv::KeyPoint, cv::Point3f> &pair)
79 {
80  return vpImagePoint(pair.first.pt.y, pair.first.pt.x);
81 }
82 
83 } // namespace
84 
85 #endif // DOXYGEN_SHOULD_SKIP_THIS
86 
87 vpKeyPoint::vpKeyPoint(const vpFeatureDetectorType &detectorType, const vpFeatureDescriptorType &descriptorType,
88  const std::string &matcherName, const vpFilterMatchingType &filterType)
89  : m_computeCovariance(false), m_covarianceMatrix(), m_currentImageId(0), m_detectionMethod(detectionScore),
90  m_detectionScore(0.15), m_detectionThreshold(100.0), m_detectionTime(0.), m_detectorNames(), m_detectors(),
91  m_extractionTime(0.), m_extractorNames(), m_extractors(), m_filteredMatches(), m_filterType(filterType),
92  m_imageFormat(jpgImageFormat), m_knnMatches(), m_mapOfImageId(), m_mapOfImages(), m_matcher(),
93  m_matcherName(matcherName), m_matches(), m_matchingFactorThreshold(2.0), m_matchingRatioThreshold(0.85),
94  m_matchingTime(0.), m_matchRansacKeyPointsToPoints(), m_nbRansacIterations(200), m_nbRansacMinInlierCount(100),
95  m_objectFilteredPoints(), m_poseTime(0.), m_queryDescriptors(), m_queryFilteredKeyPoints(), m_queryKeyPoints(),
96  m_ransacConsensusPercentage(20.0), m_ransacFilterFlag(vpPose::NO_FILTER), m_ransacInliers(), m_ransacOutliers(),
97  m_ransacParallel(false), m_ransacParallelNbThreads(0), m_ransacReprojectionError(6.0), m_ransacThreshold(0.01),
98  m_trainDescriptors(), m_trainKeyPoints(), m_trainPoints(), m_trainVpPoints(), m_useAffineDetection(false),
99 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
100  m_useBruteForceCrossCheck(true),
101 #endif
102  m_useConsensusPercentage(false), m_useKnn(false), m_useMatchTrainToQuery(false), m_useRansacVVS(true),
103  m_useSingleMatchFilter(true), m_I(), m_maxFeatures(-1)
104 {
105  initFeatureNames();
106 
107  m_detectorNames.push_back(m_mapOfDetectorNames[detectorType]);
108  m_extractorNames.push_back(m_mapOfDescriptorNames[descriptorType]);
109 
110  init();
111 }
112 
113 vpKeyPoint::vpKeyPoint(const std::string &detectorName, const std::string &extractorName,
114  const std::string &matcherName, const vpFilterMatchingType &filterType)
115  : m_computeCovariance(false), m_covarianceMatrix(), m_currentImageId(0), m_detectionMethod(detectionScore),
116  m_detectionScore(0.15), m_detectionThreshold(100.0), m_detectionTime(0.), m_detectorNames(), m_detectors(),
117  m_extractionTime(0.), m_extractorNames(), m_extractors(), m_filteredMatches(), m_filterType(filterType),
118  m_imageFormat(jpgImageFormat), m_knnMatches(), m_mapOfImageId(), m_mapOfImages(), m_matcher(),
119  m_matcherName(matcherName), m_matches(), m_matchingFactorThreshold(2.0), m_matchingRatioThreshold(0.85),
120  m_matchingTime(0.), m_matchRansacKeyPointsToPoints(), m_nbRansacIterations(200), m_nbRansacMinInlierCount(100),
121  m_objectFilteredPoints(), m_poseTime(0.), m_queryDescriptors(), m_queryFilteredKeyPoints(), m_queryKeyPoints(),
122  m_ransacConsensusPercentage(20.0), m_ransacFilterFlag(vpPose::NO_FILTER), m_ransacInliers(), m_ransacOutliers(),
123  m_ransacParallel(false), m_ransacParallelNbThreads(0), m_ransacReprojectionError(6.0), m_ransacThreshold(0.01),
124  m_trainDescriptors(), m_trainKeyPoints(), m_trainPoints(), m_trainVpPoints(), m_useAffineDetection(false),
125 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
126  m_useBruteForceCrossCheck(true),
127 #endif
128  m_useConsensusPercentage(false), m_useKnn(false), m_useMatchTrainToQuery(false), m_useRansacVVS(true),
129  m_useSingleMatchFilter(true), m_I(), m_maxFeatures(-1)
130 {
131  initFeatureNames();
132 
133  m_detectorNames.push_back(detectorName);
134  m_extractorNames.push_back(extractorName);
135 
136  init();
137 }
138 
139 vpKeyPoint::vpKeyPoint(const std::vector<std::string> &detectorNames, const std::vector<std::string> &extractorNames,
140  const std::string &matcherName, const vpFilterMatchingType &filterType)
141  : m_computeCovariance(false), m_covarianceMatrix(), m_currentImageId(0), m_detectionMethod(detectionScore),
142  m_detectionScore(0.15), m_detectionThreshold(100.0), m_detectionTime(0.), m_detectorNames(detectorNames),
143  m_detectors(), m_extractionTime(0.), m_extractorNames(extractorNames), m_extractors(), m_filteredMatches(),
144  m_filterType(filterType), m_imageFormat(jpgImageFormat), m_knnMatches(), m_mapOfImageId(), m_mapOfImages(),
145  m_matcher(), m_matcherName(matcherName), m_matches(), m_matchingFactorThreshold(2.0),
146  m_matchingRatioThreshold(0.85), m_matchingTime(0.), m_matchRansacKeyPointsToPoints(), m_nbRansacIterations(200),
147  m_nbRansacMinInlierCount(100), m_objectFilteredPoints(), m_poseTime(0.), m_queryDescriptors(),
148  m_queryFilteredKeyPoints(), m_queryKeyPoints(), m_ransacConsensusPercentage(20.0),
149  m_ransacFilterFlag(vpPose::NO_FILTER), m_ransacInliers(), m_ransacOutliers(), m_ransacParallel(false),
150  m_ransacParallelNbThreads(0), m_ransacReprojectionError(6.0), m_ransacThreshold(0.01), m_trainDescriptors(),
151  m_trainKeyPoints(), m_trainPoints(), m_trainVpPoints(), m_useAffineDetection(false),
152 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
153  m_useBruteForceCrossCheck(true),
154 #endif
155  m_useConsensusPercentage(false), m_useKnn(false), m_useMatchTrainToQuery(false), m_useRansacVVS(true),
156  m_useSingleMatchFilter(true), m_I(), m_maxFeatures(-1)
157 {
158  initFeatureNames();
159  init();
160 }
161 
162 void vpKeyPoint::affineSkew(double tilt, double phi, cv::Mat &img, cv::Mat &mask, cv::Mat &Ai)
163 {
164  int h = img.rows;
165  int w = img.cols;
166 
167  mask = cv::Mat(h, w, CV_8UC1, cv::Scalar(255));
168 
169  cv::Mat A = cv::Mat::eye(2, 3, CV_32F);
170 
171  // if (phi != 0.0) {
172  if (std::fabs(phi) > std::numeric_limits<double>::epsilon()) {
173  phi *= M_PI / 180.;
174  double s = sin(phi);
175  double c = cos(phi);
176 
177  A = (cv::Mat_<float>(2, 2) << c, -s, s, c);
178 
179  cv::Mat corners = (cv::Mat_<float>(4, 2) << 0, 0, w, 0, w, h, 0, h);
180  cv::Mat tcorners = corners * A.t();
181  cv::Mat tcorners_x, tcorners_y;
182  tcorners.col(0).copyTo(tcorners_x);
183  tcorners.col(1).copyTo(tcorners_y);
184  std::vector<cv::Mat> channels;
185  channels.push_back(tcorners_x);
186  channels.push_back(tcorners_y);
187  cv::merge(channels, tcorners);
188 
189  cv::Rect rect = cv::boundingRect(tcorners);
190  A = (cv::Mat_<float>(2, 3) << c, -s, -rect.x, s, c, -rect.y);
191 
192  cv::warpAffine(img, img, A, cv::Size(rect.width, rect.height), cv::INTER_LINEAR, cv::BORDER_REPLICATE);
193  }
194  // if (tilt != 1.0) {
195  if (std::fabs(tilt - 1.0) > std::numeric_limits<double>::epsilon()) {
196  double s = 0.8 * sqrt(tilt * tilt - 1);
197  cv::GaussianBlur(img, img, cv::Size(0, 0), s, 0.01);
198  cv::resize(img, img, cv::Size(0, 0), 1.0 / tilt, 1.0, cv::INTER_NEAREST);
199  A.row(0) = A.row(0) / tilt;
200  }
201  // if (tilt != 1.0 || phi != 0.0) {
202  if (std::fabs(tilt - 1.0) > std::numeric_limits<double>::epsilon() ||
203  std::fabs(phi) > std::numeric_limits<double>::epsilon()) {
204  h = img.rows;
205  w = img.cols;
206  cv::warpAffine(mask, mask, A, cv::Size(w, h), cv::INTER_NEAREST);
207  }
208  cv::invertAffineTransform(A, Ai);
209 }
210 
212 
213 unsigned int vpKeyPoint::buildReference(const vpImage<vpRGBa> &I_color) { return buildReference(I_color, vpRect()); }
214 
215 unsigned int vpKeyPoint::buildReference(const vpImage<unsigned char> &I, const vpImagePoint &iP, unsigned int height,
216  unsigned int width)
217 {
218  return buildReference(I, vpRect(iP, width, height));
219 }
220 
221 unsigned int vpKeyPoint::buildReference(const vpImage<vpRGBa> &I_color, const vpImagePoint &iP, unsigned int height,
222  unsigned int width)
223 {
224  return buildReference(I_color, vpRect(iP, width, height));
225 }
226 
227 unsigned int vpKeyPoint::buildReference(const vpImage<unsigned char> &I, const vpRect &rectangle)
228 {
229  // Reset variables used when dealing with 3D models
230  // So as no 3D point list is passed, we dont need this variables
231  m_trainPoints.clear();
232  m_mapOfImageId.clear();
233  m_mapOfImages.clear();
234  m_currentImageId = 1;
235 
236  if (m_useAffineDetection) {
237  std::vector<std::vector<cv::KeyPoint> > listOfTrainKeyPoints;
238  std::vector<cv::Mat> listOfTrainDescriptors;
239 
240  // Detect keypoints and extract descriptors on multiple images
241  detectExtractAffine(I, listOfTrainKeyPoints, listOfTrainDescriptors);
242 
243  // Flatten the different train lists
244  m_trainKeyPoints.clear();
245  for (std::vector<std::vector<cv::KeyPoint> >::const_iterator it = listOfTrainKeyPoints.begin();
246  it != listOfTrainKeyPoints.end(); ++it) {
247  m_trainKeyPoints.insert(m_trainKeyPoints.end(), it->begin(), it->end());
248  }
249 
250  bool first = true;
251  for (std::vector<cv::Mat>::const_iterator it = listOfTrainDescriptors.begin(); it != listOfTrainDescriptors.end();
252  ++it) {
253  if (first) {
254  first = false;
255  it->copyTo(m_trainDescriptors);
256  }
257  else {
258  m_trainDescriptors.push_back(*it);
259  }
260  }
261  }
262  else {
263  detect(I, m_trainKeyPoints, m_detectionTime, rectangle);
264  extract(I, m_trainKeyPoints, m_trainDescriptors, m_extractionTime);
265  }
266 
267  // Save the correspondence keypoint class_id with the training image_id in a map.
268  // Used to display the matching with all the training images.
269  for (std::vector<cv::KeyPoint>::const_iterator it = m_trainKeyPoints.begin(); it != m_trainKeyPoints.end(); ++it) {
270  m_mapOfImageId[it->class_id] = m_currentImageId;
271  }
272 
273  // Save the image in a map at a specific image_id
274  m_mapOfImages[m_currentImageId] = I;
275 
276  // Convert OpenCV type to ViSP type for compatibility
278 
279  m_reference_computed = true;
280 
281  // Add train descriptors in matcher object
282  m_matcher->clear();
283  m_matcher->add(std::vector<cv::Mat>(1, m_trainDescriptors));
284 
285  return static_cast<unsigned int>(m_trainKeyPoints.size());
286 }
287 
288 unsigned int vpKeyPoint::buildReference(const vpImage<vpRGBa> &I_color, const vpRect &rectangle)
289 {
290  vpImageConvert::convert(I_color, m_I);
291  return (buildReference(m_I, rectangle));
292 }
293 
294 unsigned int vpKeyPoint::buildReference(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &trainKeyPoints,
295  std::vector<cv::Point3f> &points3f, bool append, int class_id)
296 {
297  cv::Mat trainDescriptors;
298  // Copy the input list of keypoints
299  std::vector<cv::KeyPoint> trainKeyPoints_tmp = trainKeyPoints;
300 
301  extract(I, trainKeyPoints, trainDescriptors, m_extractionTime, &points3f);
302 
303  if (trainKeyPoints.size() != trainKeyPoints_tmp.size()) {
304  // Keypoints have been removed
305  // Store the hash of a keypoint as the key and the index of the keypoint
306  // as the value
307  std::map<size_t, size_t> mapOfKeypointHashes;
308  size_t cpt = 0;
309  for (std::vector<cv::KeyPoint>::const_iterator it = trainKeyPoints_tmp.begin(); it != trainKeyPoints_tmp.end();
310  ++it, cpt++) {
311  mapOfKeypointHashes[myKeypointHash(*it)] = cpt;
312  }
313 
314  std::vector<cv::Point3f> trainPoints_tmp;
315  for (std::vector<cv::KeyPoint>::const_iterator it = trainKeyPoints.begin(); it != trainKeyPoints.end(); ++it) {
316  if (mapOfKeypointHashes.find(myKeypointHash(*it)) != mapOfKeypointHashes.end()) {
317  trainPoints_tmp.push_back(points3f[mapOfKeypointHashes[myKeypointHash(*it)]]);
318  }
319  }
320 
321  // Copy trainPoints_tmp to points3f
322  points3f = trainPoints_tmp;
323  }
324 
325  return (buildReference(I, trainKeyPoints, trainDescriptors, points3f, append, class_id));
326 }
327 
328 unsigned int vpKeyPoint::buildReference(const vpImage<vpRGBa> &I_color, std::vector<cv::KeyPoint> &trainKeyPoints,
329  std::vector<cv::Point3f> &points3f, bool append, int class_id)
330 {
331  cv::Mat trainDescriptors;
332  // Copy the input list of keypoints
333  std::vector<cv::KeyPoint> trainKeyPoints_tmp = trainKeyPoints;
334 
335  extract(I_color, trainKeyPoints, trainDescriptors, m_extractionTime, &points3f);
336 
337  if (trainKeyPoints.size() != trainKeyPoints_tmp.size()) {
338  // Keypoints have been removed
339  // Store the hash of a keypoint as the key and the index of the keypoint
340  // as the value
341  std::map<size_t, size_t> mapOfKeypointHashes;
342  size_t cpt = 0;
343  for (std::vector<cv::KeyPoint>::const_iterator it = trainKeyPoints_tmp.begin(); it != trainKeyPoints_tmp.end();
344  ++it, cpt++) {
345  mapOfKeypointHashes[myKeypointHash(*it)] = cpt;
346  }
347 
348  std::vector<cv::Point3f> trainPoints_tmp;
349  for (std::vector<cv::KeyPoint>::const_iterator it = trainKeyPoints.begin(); it != trainKeyPoints.end(); ++it) {
350  if (mapOfKeypointHashes.find(myKeypointHash(*it)) != mapOfKeypointHashes.end()) {
351  trainPoints_tmp.push_back(points3f[mapOfKeypointHashes[myKeypointHash(*it)]]);
352  }
353  }
354 
355  // Copy trainPoints_tmp to points3f
356  points3f = trainPoints_tmp;
357  }
358 
359  return (buildReference(I_color, trainKeyPoints, trainDescriptors, points3f, append, class_id));
360 }
361 
362 
364  const std::vector<cv::KeyPoint> &trainKeyPoints,
365  const cv::Mat &trainDescriptors, const std::vector<cv::Point3f> &points3f,
366  bool append, int class_id)
367 {
368  if (!append) {
369  m_trainPoints.clear();
370  m_mapOfImageId.clear();
371  m_mapOfImages.clear();
372  m_currentImageId = 0;
373  m_trainKeyPoints.clear();
374  }
375 
376  m_currentImageId++;
377 
378  std::vector<cv::KeyPoint> trainKeyPoints_tmp = trainKeyPoints;
379  // Set class_id if != -1
380  if (class_id != -1) {
381  for (std::vector<cv::KeyPoint>::iterator it = trainKeyPoints_tmp.begin(); it != trainKeyPoints_tmp.end(); ++it) {
382  it->class_id = class_id;
383  }
384  }
385 
386  // Save the correspondence keypoint class_id with the training image_id in a map.
387  // Used to display the matching with all the training images.
388  for (std::vector<cv::KeyPoint>::const_iterator it = trainKeyPoints_tmp.begin(); it != trainKeyPoints_tmp.end();
389  ++it) {
390  m_mapOfImageId[it->class_id] = m_currentImageId;
391  }
392 
393  // Save the image in a map at a specific image_id
394  m_mapOfImages[m_currentImageId] = I;
395 
396  // Append reference lists
397  m_trainKeyPoints.insert(m_trainKeyPoints.end(), trainKeyPoints_tmp.begin(), trainKeyPoints_tmp.end());
398  if (!append) {
399  trainDescriptors.copyTo(m_trainDescriptors);
400  }
401  else {
402  m_trainDescriptors.push_back(trainDescriptors);
403  }
404  this->m_trainPoints.insert(m_trainPoints.end(), points3f.begin(), points3f.end());
405 
406  // Convert OpenCV type to ViSP type for compatibility
408  vpConvert::convertFromOpenCV(m_trainPoints, m_trainVpPoints);
409 
410  // Add train descriptors in matcher object
411  m_matcher->clear();
412  m_matcher->add(std::vector<cv::Mat>(1, m_trainDescriptors));
413 
414  m_reference_computed = true;
415 
416  return static_cast<unsigned int>(m_trainKeyPoints.size());
417 }
418 
419 unsigned int vpKeyPoint::buildReference(const vpImage<vpRGBa> &I_color, const std::vector<cv::KeyPoint> &trainKeyPoints,
420  const cv::Mat &trainDescriptors, const std::vector<cv::Point3f> &points3f,
421  bool append, int class_id)
422 {
423  vpImageConvert::convert(I_color, m_I);
424  return (buildReference(m_I, trainKeyPoints, trainDescriptors, points3f, append, class_id));
425 }
426 
427 void vpKeyPoint::compute3D(const cv::KeyPoint &candidate, const std::vector<vpPoint> &roi,
428  const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, cv::Point3f &point)
429 {
430  /* compute plane equation */
431  std::vector<vpPoint>::const_iterator it_roi = roi.begin();
432  vpPoint pts[3];
433  pts[0] = *it_roi;
434  ++it_roi;
435  pts[1] = *it_roi;
436  ++it_roi;
437  pts[2] = *it_roi;
438  vpPlane Po(pts[0], pts[1], pts[2]);
439  double xc = 0.0, yc = 0.0;
440  vpPixelMeterConversion::convertPoint(cam, candidate.pt.x, candidate.pt.y, xc, yc);
441  double Z = -Po.getD() / (Po.getA() * xc + Po.getB() * yc + Po.getC());
442  double X = xc * Z;
443  double Y = yc * Z;
444  vpColVector point_cam(4);
445  point_cam[0] = X;
446  point_cam[1] = Y;
447  point_cam[2] = Z;
448  point_cam[3] = 1;
449  vpColVector point_obj(4);
450  point_obj = cMo.inverse() * point_cam;
451  point = cv::Point3f((float)point_obj[0], (float)point_obj[1], (float)point_obj[2]);
452 }
453 
454 void vpKeyPoint::compute3D(const vpImagePoint &candidate, const std::vector<vpPoint> &roi,
455  const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, vpPoint &point)
456 {
457  /* compute plane equation */
458  std::vector<vpPoint>::const_iterator it_roi = roi.begin();
459  vpPoint pts[3];
460  pts[0] = *it_roi;
461  ++it_roi;
462  pts[1] = *it_roi;
463  ++it_roi;
464  pts[2] = *it_roi;
465  vpPlane Po(pts[0], pts[1], pts[2]);
466  double xc = 0.0, yc = 0.0;
467  vpPixelMeterConversion::convertPoint(cam, candidate, xc, yc);
468  double Z = -Po.getD() / (Po.getA() * xc + Po.getB() * yc + Po.getC());
469  double X = xc * Z;
470  double Y = yc * Z;
471  vpColVector point_cam(4);
472  point_cam[0] = X;
473  point_cam[1] = Y;
474  point_cam[2] = Z;
475  point_cam[3] = 1;
476  vpColVector point_obj(4);
477  point_obj = cMo.inverse() * point_cam;
478  point.setWorldCoordinates(point_obj);
479 }
480 
482  std::vector<cv::KeyPoint> &candidates,
483  const std::vector<vpPolygon> &polygons,
484  const std::vector<std::vector<vpPoint> > &roisPt,
485  std::vector<cv::Point3f> &points, cv::Mat *descriptors)
486 {
487  std::vector<cv::KeyPoint> candidatesToCheck = candidates;
488  candidates.clear();
489  points.clear();
490  vpImagePoint imPt;
491  cv::Point3f pt;
492  cv::Mat desc;
493 
494  std::vector<std::pair<cv::KeyPoint, size_t> > pairOfCandidatesToCheck(candidatesToCheck.size());
495  for (size_t i = 0; i < candidatesToCheck.size(); i++) {
496  pairOfCandidatesToCheck[i] = std::pair<cv::KeyPoint, size_t>(candidatesToCheck[i], i);
497  }
498 
499  size_t cpt1 = 0;
500  std::vector<vpPolygon> polygons_tmp = polygons;
501  for (std::vector<vpPolygon>::iterator it1 = polygons_tmp.begin(); it1 != polygons_tmp.end(); ++it1, cpt1++) {
502  std::vector<std::pair<cv::KeyPoint, size_t> >::iterator it2 = pairOfCandidatesToCheck.begin();
503 
504  while (it2 != pairOfCandidatesToCheck.end()) {
505  imPt.set_ij(it2->first.pt.y, it2->first.pt.x);
506  if (it1->isInside(imPt)) {
507  candidates.push_back(it2->first);
508  vpKeyPoint::compute3D(it2->first, roisPt[cpt1], cam, cMo, pt);
509  points.push_back(pt);
510 
511  if (descriptors != nullptr) {
512  desc.push_back(descriptors->row((int)it2->second));
513  }
514 
515  // Remove candidate keypoint which is located on the current polygon
516  it2 = pairOfCandidatesToCheck.erase(it2);
517  }
518  else {
519  ++it2;
520  }
521  }
522  }
523 
524  if (descriptors != nullptr) {
525  desc.copyTo(*descriptors);
526  }
527 }
528 
530  std::vector<vpImagePoint> &candidates,
531  const std::vector<vpPolygon> &polygons,
532  const std::vector<std::vector<vpPoint> > &roisPt,
533  std::vector<vpPoint> &points, cv::Mat *descriptors)
534 {
535  std::vector<vpImagePoint> candidatesToCheck = candidates;
536  candidates.clear();
537  points.clear();
538  vpPoint pt;
539  cv::Mat desc;
540 
541  std::vector<std::pair<vpImagePoint, size_t> > pairOfCandidatesToCheck(candidatesToCheck.size());
542  for (size_t i = 0; i < candidatesToCheck.size(); i++) {
543  pairOfCandidatesToCheck[i] = std::pair<vpImagePoint, size_t>(candidatesToCheck[i], i);
544  }
545 
546  size_t cpt1 = 0;
547  std::vector<vpPolygon> polygons_tmp = polygons;
548  for (std::vector<vpPolygon>::iterator it1 = polygons_tmp.begin(); it1 != polygons_tmp.end(); ++it1, cpt1++) {
549  std::vector<std::pair<vpImagePoint, size_t> >::iterator it2 = pairOfCandidatesToCheck.begin();
550 
551  while (it2 != pairOfCandidatesToCheck.end()) {
552  if (it1->isInside(it2->first)) {
553  candidates.push_back(it2->first);
554  vpKeyPoint::compute3D(it2->first, roisPt[cpt1], cam, cMo, pt);
555  points.push_back(pt);
556 
557  if (descriptors != nullptr) {
558  desc.push_back(descriptors->row((int)it2->second));
559  }
560 
561  // Remove candidate keypoint which is located on the current polygon
562  it2 = pairOfCandidatesToCheck.erase(it2);
563  }
564  else {
565  ++it2;
566  }
567  }
568  }
569 }
570 
571 
573  std::vector<cv::KeyPoint> &candidates, const std::vector<vpCylinder> &cylinders,
574  const std::vector<std::vector<std::vector<vpImagePoint> > > &vectorOfCylinderRois,
575  std::vector<cv::Point3f> &points, cv::Mat *descriptors)
576 {
577  std::vector<cv::KeyPoint> candidatesToCheck = candidates;
578  candidates.clear();
579  points.clear();
580  cv::Mat desc;
581 
582  // Keep only keypoints on cylinders
583  size_t cpt_keypoint = 0;
584  for (std::vector<cv::KeyPoint>::const_iterator it1 = candidatesToCheck.begin(); it1 != candidatesToCheck.end();
585  ++it1, cpt_keypoint++) {
586  size_t cpt_cylinder = 0;
587 
588  // Iterate through the list of vpCylinders
589  for (std::vector<std::vector<std::vector<vpImagePoint> > >::const_iterator it2 = vectorOfCylinderRois.begin();
590  it2 != vectorOfCylinderRois.end(); ++it2, cpt_cylinder++) {
591  // Iterate through the list of the bounding boxes of the current
592  // vpCylinder
593  for (std::vector<std::vector<vpImagePoint> >::const_iterator it3 = it2->begin(); it3 != it2->end(); ++it3) {
594  if (vpPolygon::isInside(*it3, it1->pt.y, it1->pt.x)) {
595  candidates.push_back(*it1);
596 
597  // Calculate the 3D coordinates for each keypoint located on
598  // cylinders
599  double xm = 0.0, ym = 0.0;
600  vpPixelMeterConversion::convertPoint(cam, it1->pt.x, it1->pt.y, xm, ym);
601  double Z = cylinders[cpt_cylinder].computeZ(xm, ym);
602 
603  if (!vpMath::isNaN(Z) && Z > std::numeric_limits<double>::epsilon()) {
604  vpColVector point_cam(4);
605  point_cam[0] = xm * Z;
606  point_cam[1] = ym * Z;
607  point_cam[2] = Z;
608  point_cam[3] = 1;
609  vpColVector point_obj(4);
610  point_obj = cMo.inverse() * point_cam;
611  vpPoint pt;
612  pt.setWorldCoordinates(point_obj);
613  points.push_back(cv::Point3f((float)pt.get_oX(), (float)pt.get_oY(), (float)pt.get_oZ()));
614 
615  if (descriptors != nullptr) {
616  desc.push_back(descriptors->row((int)cpt_keypoint));
617  }
618 
619  break;
620  }
621  }
622  }
623  }
624  }
625 
626  if (descriptors != nullptr) {
627  desc.copyTo(*descriptors);
628  }
629 }
630 
632  std::vector<vpImagePoint> &candidates, const std::vector<vpCylinder> &cylinders,
633  const std::vector<std::vector<std::vector<vpImagePoint> > > &vectorOfCylinderRois,
634  std::vector<vpPoint> &points, cv::Mat *descriptors)
635 {
636  std::vector<vpImagePoint> candidatesToCheck = candidates;
637  candidates.clear();
638  points.clear();
639  cv::Mat desc;
640 
641  // Keep only keypoints on cylinders
642  size_t cpt_keypoint = 0;
643  for (std::vector<vpImagePoint>::const_iterator it1 = candidatesToCheck.begin(); it1 != candidatesToCheck.end();
644  ++it1, cpt_keypoint++) {
645  size_t cpt_cylinder = 0;
646 
647  // Iterate through the list of vpCylinders
648  for (std::vector<std::vector<std::vector<vpImagePoint> > >::const_iterator it2 = vectorOfCylinderRois.begin();
649  it2 != vectorOfCylinderRois.end(); ++it2, cpt_cylinder++) {
650  // Iterate through the list of the bounding boxes of the current
651  // vpCylinder
652  for (std::vector<std::vector<vpImagePoint> >::const_iterator it3 = it2->begin(); it3 != it2->end(); ++it3) {
653  if (vpPolygon::isInside(*it3, it1->get_i(), it1->get_j())) {
654  candidates.push_back(*it1);
655 
656  // Calculate the 3D coordinates for each keypoint located on
657  // cylinders
658  double xm = 0.0, ym = 0.0;
659  vpPixelMeterConversion::convertPoint(cam, it1->get_u(), it1->get_v(), xm, ym);
660  double Z = cylinders[cpt_cylinder].computeZ(xm, ym);
661 
662  if (!vpMath::isNaN(Z) && Z > std::numeric_limits<double>::epsilon()) {
663  vpColVector point_cam(4);
664  point_cam[0] = xm * Z;
665  point_cam[1] = ym * Z;
666  point_cam[2] = Z;
667  point_cam[3] = 1;
668  vpColVector point_obj(4);
669  point_obj = cMo.inverse() * point_cam;
670  vpPoint pt;
671  pt.setWorldCoordinates(point_obj);
672  points.push_back(pt);
673 
674  if (descriptors != nullptr) {
675  desc.push_back(descriptors->row((int)cpt_keypoint));
676  }
677 
678  break;
679  }
680  }
681  }
682  }
683  }
684 
685  if (descriptors != nullptr) {
686  desc.copyTo(*descriptors);
687  }
688 }
689 
690 bool vpKeyPoint::computePose(const std::vector<cv::Point2f> &imagePoints, const std::vector<cv::Point3f> &objectPoints,
691  const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, std::vector<int> &inlierIndex,
692  double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &))
693 {
694  double t = vpTime::measureTimeMs();
695 
696  if (imagePoints.size() < 4 || objectPoints.size() < 4 || imagePoints.size() != objectPoints.size()) {
697  elapsedTime = (vpTime::measureTimeMs() - t);
698  std::cerr << "Not enough points to compute the pose (at least 4 points "
699  "are needed)."
700  << std::endl;
701 
702  return false;
703  }
704 
705  cv::Mat cameraMatrix =
706  (cv::Mat_<double>(3, 3) << cam.get_px(), 0, cam.get_u0(), 0, cam.get_py(), cam.get_v0(), 0, 0, 1);
707  cv::Mat rvec, tvec;
708 
709  // Bug with OpenCV < 2.4.0 when zero distortion is provided by an empty
710  // array. http://code.opencv.org/issues/1700 ;
711  // http://code.opencv.org/issues/1718 what(): Distortion coefficients must
712  // be 1x4, 4x1, 1x5, 5x1, 1x8 or 8x1 floating-point vector in function
713  // cvProjectPoints2 Fixed in OpenCV 2.4.0 (r7558)
714  // cv::Mat distCoeffs;
715  cv::Mat distCoeffs = cv::Mat::zeros(1, 5, CV_64F);
716 
717  try {
718 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
719  // OpenCV 3.0.0 (2014/12/12)
720  cv::solvePnPRansac(objectPoints, imagePoints, cameraMatrix, distCoeffs, rvec, tvec, false, m_nbRansacIterations,
721  (float)m_ransacReprojectionError,
722  0.99, // confidence=0.99 (default) – The probability
723  // that the algorithm produces a useful result.
724  inlierIndex, cv::SOLVEPNP_ITERATIVE);
725  // SOLVEPNP_ITERATIVE (default): Iterative method is based on
726  // Levenberg-Marquardt optimization. In this case the function finds such a
727  // pose that minimizes reprojection error, that is the sum of squared
728  // distances between the observed projections imagePoints and the projected
729  // (using projectPoints() ) objectPoints . SOLVEPNP_P3P: Method is based on
730  // the paper of X.S. Gao, X.-R. Hou, J. Tang, H.-F. Chang “Complete Solution
731  // Classification for the Perspective-Three-Point Problem”. In this case the
732  // function requires exactly four object and image points. SOLVEPNP_EPNP:
733  // Method has been introduced by F.Moreno-Noguer, V.Lepetit and P.Fua in the
734  // paper “EPnP: Efficient Perspective-n-Point Camera Pose Estimation”.
735  // SOLVEPNP_DLS: Method is based on the paper of Joel A. Hesch and Stergios I.
736  // Roumeliotis. “A Direct Least-Squares (DLS) Method for PnP”. SOLVEPNP_UPNP
737  // Method is based on the paper of A.Penate-Sanchez, J.Andrade-Cetto,
738  // F.Moreno-Noguer. “Exhaustive Linearization for Robust Camera Pose and Focal
739  // Length Estimation”. In this case the function also estimates the
740  // parameters
741  // f_x and f_y assuming that both have the same value. Then the cameraMatrix
742  // is updated with the estimated focal length.
743 #else
744  int nbInlierToReachConsensus = m_nbRansacMinInlierCount;
745  if (m_useConsensusPercentage) {
746  nbInlierToReachConsensus = (int)(m_ransacConsensusPercentage / 100.0 * (double)m_queryFilteredKeyPoints.size());
747  }
748 
749  cv::solvePnPRansac(objectPoints, imagePoints, cameraMatrix, distCoeffs, rvec, tvec, false, m_nbRansacIterations,
750  (float)m_ransacReprojectionError, nbInlierToReachConsensus, inlierIndex);
751 #endif
752  }
753  catch (cv::Exception &e) {
754  std::cerr << e.what() << std::endl;
755  elapsedTime = (vpTime::measureTimeMs() - t);
756  return false;
757  }
758  vpTranslationVector translationVec(tvec.at<double>(0), tvec.at<double>(1), tvec.at<double>(2));
759  vpThetaUVector thetaUVector(rvec.at<double>(0), rvec.at<double>(1), rvec.at<double>(2));
760  cMo = vpHomogeneousMatrix(translationVec, thetaUVector);
761 
762  if (func != nullptr) {
763  // Check the final pose returned by solvePnPRansac to discard
764  // solutions which do not respect the pose criterion.
765  if (!func(cMo)) {
766  elapsedTime = (vpTime::measureTimeMs() - t);
767  return false;
768  }
769  }
770 
771  elapsedTime = (vpTime::measureTimeMs() - t);
772  return true;
773 }
774 
775 bool vpKeyPoint::computePose(const std::vector<vpPoint> &objectVpPoints, vpHomogeneousMatrix &cMo,
776  std::vector<vpPoint> &inliers, double &elapsedTime,
777  bool (*func)(const vpHomogeneousMatrix &))
778 {
779  std::vector<unsigned int> inlierIndex;
780  return computePose(objectVpPoints, cMo, inliers, inlierIndex, elapsedTime, func);
781 }
782 
783 bool vpKeyPoint::computePose(const std::vector<vpPoint> &objectVpPoints, vpHomogeneousMatrix &cMo,
784  std::vector<vpPoint> &inliers, std::vector<unsigned int> &inlierIndex, double &elapsedTime,
785  bool (*func)(const vpHomogeneousMatrix &))
786 {
787  double t = vpTime::measureTimeMs();
788 
789  if (objectVpPoints.size() < 4) {
790  elapsedTime = (vpTime::measureTimeMs() - t);
791  // std::cerr << "Not enough points to compute the pose (at least 4
792  // points are needed)." << std::endl;
793 
794  return false;
795  }
796 
797  vpPose pose;
798 
799  for (std::vector<vpPoint>::const_iterator it = objectVpPoints.begin(); it != objectVpPoints.end(); ++it) {
800  pose.addPoint(*it);
801  }
802 
803  unsigned int nbInlierToReachConsensus = (unsigned int)m_nbRansacMinInlierCount;
804  if (m_useConsensusPercentage) {
805  nbInlierToReachConsensus =
806  (unsigned int)(m_ransacConsensusPercentage / 100.0 * (double)m_queryFilteredKeyPoints.size());
807  }
808 
809  pose.setRansacFilterFlag(m_ransacFilterFlag);
810  pose.setUseParallelRansac(m_ransacParallel);
811  pose.setNbParallelRansacThreads(m_ransacParallelNbThreads);
812  pose.setRansacNbInliersToReachConsensus(nbInlierToReachConsensus);
813  pose.setRansacThreshold(m_ransacThreshold);
814  pose.setRansacMaxTrials(m_nbRansacIterations);
815 
816  bool isRansacPoseEstimationOk = false;
817  try {
818  pose.setCovarianceComputation(m_computeCovariance);
819  isRansacPoseEstimationOk = pose.computePose(vpPose::RANSAC, cMo, func);
820  inliers = pose.getRansacInliers();
821  inlierIndex = pose.getRansacInlierIndex();
822 
823  if (m_computeCovariance) {
824  m_covarianceMatrix = pose.getCovarianceMatrix();
825  }
826  }
827  catch (const vpException &e) {
828  std::cerr << "e=" << e.what() << std::endl;
829  elapsedTime = (vpTime::measureTimeMs() - t);
830  return false;
831  }
832 
833  // if(func != nullptr && isRansacPoseEstimationOk) {
834  // //Check the final pose returned by the Ransac VVS pose estimation as
835  // in rare some cases
836  // //we can converge toward a final cMo that does not respect the pose
837  // criterion even
838  // //if the 4 minimal points picked to respect the pose criterion.
839  // if(!func(&cMo)) {
840  // elapsedTime = (vpTime::measureTimeMs() - t);
841  // return false;
842  // }
843  // }
844 
845  elapsedTime = (vpTime::measureTimeMs() - t);
846  return isRansacPoseEstimationOk;
847 }
848 
849 double vpKeyPoint::computePoseEstimationError(const std::vector<std::pair<cv::KeyPoint, cv::Point3f> > &matchKeyPoints,
850  const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo_est)
851 {
852  if (matchKeyPoints.size() == 0) {
853  // return std::numeric_limits<double>::max(); // create an error under
854  // Windows. To fix it we have to add #undef max
855  return DBL_MAX;
856  }
857 
858  std::vector<double> errors(matchKeyPoints.size());
859  size_t cpt = 0;
860  vpPoint pt;
861  for (std::vector<std::pair<cv::KeyPoint, cv::Point3f> >::const_iterator it = matchKeyPoints.begin();
862  it != matchKeyPoints.end(); ++it, cpt++) {
863  pt.set_oX(it->second.x);
864  pt.set_oY(it->second.y);
865  pt.set_oZ(it->second.z);
866  pt.project(cMo_est);
867  double u = 0.0, v = 0.0;
868  vpMeterPixelConversion::convertPoint(cam, pt.get_x(), pt.get_y(), u, v);
869  errors[cpt] = std::sqrt((u - it->first.pt.x) * (u - it->first.pt.x) + (v - it->first.pt.y) * (v - it->first.pt.y));
870  }
871 
872  return std::accumulate(errors.begin(), errors.end(), 0.0) / errors.size();
873 }
874 
876  vpImage<unsigned char> &IMatching)
877 {
878  // Image matching side by side
879  unsigned int width = IRef.getWidth() + ICurrent.getWidth();
880  unsigned int height = std::max<unsigned int>(IRef.getHeight(), ICurrent.getHeight());
881 
882  IMatching = vpImage<unsigned char>(height, width);
883 }
884 
886  vpImage<vpRGBa> &IMatching)
887 {
888  // Image matching side by side
889  unsigned int width = IRef.getWidth() + ICurrent.getWidth();
890  unsigned int height = std::max<unsigned int>(IRef.getHeight(), ICurrent.getHeight());
891 
892  IMatching = vpImage<vpRGBa>(height, width);
893 }
894 
896 {
897  // Nb images in the training database + the current image we want to detect
898  // the object
899  unsigned int nbImg = (unsigned int)(m_mapOfImages.size() + 1);
900 
901  if (m_mapOfImages.empty()) {
902  std::cerr << "There is no training image loaded !" << std::endl;
903  return;
904  }
905 
906  if (nbImg == 2) {
907  // Only one training image, so we display them side by side
908  createImageMatching(m_mapOfImages.begin()->second, ICurrent, IMatching);
909  }
910  else {
911  // Multiple training images, display them as a mosaic image
912  // (unsigned int) std::floor(std::sqrt((double) nbImg) + 0.5);
913  unsigned int nbImgSqrt = (unsigned int)vpMath::round(std::sqrt((double)nbImg));
914 
915  // Number of columns in the mosaic grid
916  unsigned int nbWidth = nbImgSqrt;
917  // Number of rows in the mosaic grid
918  unsigned int nbHeight = nbImgSqrt;
919 
920  // Deals with non square mosaic grid and the total number of images
921  if (nbImgSqrt * nbImgSqrt < nbImg) {
922  nbWidth++;
923  }
924 
925  unsigned int maxW = ICurrent.getWidth();
926  unsigned int maxH = ICurrent.getHeight();
927  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
928  ++it) {
929  if (maxW < it->second.getWidth()) {
930  maxW = it->second.getWidth();
931  }
932 
933  if (maxH < it->second.getHeight()) {
934  maxH = it->second.getHeight();
935  }
936  }
937 
938  IMatching = vpImage<unsigned char>(maxH * nbHeight, maxW * nbWidth);
939  }
940 }
941 
943 {
944  // Nb images in the training database + the current image we want to detect
945  // the object
946  unsigned int nbImg = (unsigned int)(m_mapOfImages.size() + 1);
947 
948  if (m_mapOfImages.empty()) {
949  std::cerr << "There is no training image loaded !" << std::endl;
950  return;
951  }
952 
953  if (nbImg == 2) {
954  // Only one training image, so we display them side by side
955  createImageMatching(m_mapOfImages.begin()->second, ICurrent, IMatching);
956  }
957  else {
958  // Multiple training images, display them as a mosaic image
959  //(unsigned int) std::floor(std::sqrt((double) nbImg) + 0.5);
960  unsigned int nbImgSqrt = (unsigned int)vpMath::round(std::sqrt((double)nbImg));
961 
962  // Number of columns in the mosaic grid
963  unsigned int nbWidth = nbImgSqrt;
964  // Number of rows in the mosaic grid
965  unsigned int nbHeight = nbImgSqrt;
966 
967  // Deals with non square mosaic grid and the total number of images
968  if (nbImgSqrt * nbImgSqrt < nbImg) {
969  nbWidth++;
970  }
971 
972  unsigned int maxW = ICurrent.getWidth();
973  unsigned int maxH = ICurrent.getHeight();
974  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
975  ++it) {
976  if (maxW < it->second.getWidth()) {
977  maxW = it->second.getWidth();
978  }
979 
980  if (maxH < it->second.getHeight()) {
981  maxH = it->second.getHeight();
982  }
983  }
984 
985  IMatching = vpImage<vpRGBa>(maxH * nbHeight, maxW * nbWidth);
986  }
987 }
988 
989 void vpKeyPoint::detect(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &keyPoints, const vpRect &rectangle)
990 {
991  double elapsedTime;
992  detect(I, keyPoints, elapsedTime, rectangle);
993 }
994 
995 void vpKeyPoint::detect(const vpImage<vpRGBa> &I_color, std::vector<cv::KeyPoint> &keyPoints, const vpRect &rectangle)
996 {
997  double elapsedTime;
998  detect(I_color, keyPoints, elapsedTime, rectangle);
999 }
1000 
1001 void vpKeyPoint::detect(const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, const cv::Mat &mask)
1002 {
1003  double elapsedTime;
1004  detect(matImg, keyPoints, elapsedTime, mask);
1005 }
1006 
1007 void vpKeyPoint::detect(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &keyPoints, double &elapsedTime,
1008  const vpRect &rectangle)
1009 {
1010  cv::Mat matImg;
1011  vpImageConvert::convert(I, matImg, false);
1012  cv::Mat mask = cv::Mat::zeros(matImg.rows, matImg.cols, CV_8U);
1013 
1014  if (rectangle.getWidth() > 0 && rectangle.getHeight() > 0) {
1015 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
1016  int filled = cv::FILLED;
1017 #else
1018  int filled = CV_FILLED;
1019 #endif
1020  cv::Point leftTop((int)rectangle.getLeft(), (int)rectangle.getTop()),
1021  rightBottom((int)rectangle.getRight(), (int)rectangle.getBottom());
1022  cv::rectangle(mask, leftTop, rightBottom, cv::Scalar(255), filled);
1023  }
1024  else {
1025  mask = cv::Mat::ones(matImg.rows, matImg.cols, CV_8U) * 255;
1026  }
1027 
1028  detect(matImg, keyPoints, elapsedTime, mask);
1029 }
1030 
1031 void vpKeyPoint::detect(const vpImage<vpRGBa> &I_color, std::vector<cv::KeyPoint> &keyPoints, double &elapsedTime,
1032  const vpRect &rectangle)
1033 {
1034  cv::Mat matImg;
1035  vpImageConvert::convert(I_color, matImg);
1036  cv::Mat mask = cv::Mat::zeros(matImg.rows, matImg.cols, CV_8U);
1037 
1038  if (rectangle.getWidth() > 0 && rectangle.getHeight() > 0) {
1039 #if VISP_HAVE_OPENCV_VERSION >= 0x030000
1040  int filled = cv::FILLED;
1041 #else
1042  int filled = CV_FILLED;
1043 #endif
1044  cv::Point leftTop((int)rectangle.getLeft(), (int)rectangle.getTop()),
1045  rightBottom((int)rectangle.getRight(), (int)rectangle.getBottom());
1046  cv::rectangle(mask, leftTop, rightBottom, cv::Scalar(255), filled);
1047  }
1048  else {
1049  mask = cv::Mat::ones(matImg.rows, matImg.cols, CV_8U) * 255;
1050  }
1051 
1052  detect(matImg, keyPoints, elapsedTime, mask);
1053 }
1054 
1055 void vpKeyPoint::detect(const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, double &elapsedTime,
1056  const cv::Mat &mask)
1057 {
1058  double t = vpTime::measureTimeMs();
1059  keyPoints.clear();
1060 
1061  for (std::map<std::string, cv::Ptr<cv::FeatureDetector> >::const_iterator it = m_detectors.begin();
1062  it != m_detectors.end(); ++it) {
1063  std::vector<cv::KeyPoint> kp;
1064 
1065  it->second->detect(matImg, kp, mask);
1066  keyPoints.insert(keyPoints.end(), kp.begin(), kp.end());
1067  }
1068 
1069  elapsedTime = vpTime::measureTimeMs() - t;
1070 }
1071 
1072 void vpKeyPoint::display(const vpImage<unsigned char> &IRef, const vpImage<unsigned char> &ICurrent, unsigned int size)
1073 {
1074  std::vector<vpImagePoint> vpQueryImageKeyPoints;
1075  getQueryKeyPoints(vpQueryImageKeyPoints);
1076  std::vector<vpImagePoint> vpTrainImageKeyPoints;
1077  getTrainKeyPoints(vpTrainImageKeyPoints);
1078 
1079  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1080  vpDisplay::displayCross(IRef, vpTrainImageKeyPoints[(size_t)(it->trainIdx)], size, vpColor::red);
1081  vpDisplay::displayCross(ICurrent, vpQueryImageKeyPoints[(size_t)(it->queryIdx)], size, vpColor::green);
1082  }
1083 }
1084 
1085 void vpKeyPoint::display(const vpImage<vpRGBa> &IRef, const vpImage<vpRGBa> &ICurrent, unsigned int size)
1086 {
1087  std::vector<vpImagePoint> vpQueryImageKeyPoints;
1088  getQueryKeyPoints(vpQueryImageKeyPoints);
1089  std::vector<vpImagePoint> vpTrainImageKeyPoints;
1090  getTrainKeyPoints(vpTrainImageKeyPoints);
1091 
1092  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1093  vpDisplay::displayCross(IRef, vpTrainImageKeyPoints[(size_t)(it->trainIdx)], size, vpColor::red);
1094  vpDisplay::displayCross(ICurrent, vpQueryImageKeyPoints[(size_t)(it->queryIdx)], size, vpColor::green);
1095  }
1096 }
1097 
1098 void vpKeyPoint::display(const vpImage<unsigned char> &ICurrent, unsigned int size, const vpColor &color)
1099 {
1100  std::vector<vpImagePoint> vpQueryImageKeyPoints;
1101  getQueryKeyPoints(vpQueryImageKeyPoints);
1102 
1103  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1104  vpDisplay::displayCross(ICurrent, vpQueryImageKeyPoints[(size_t)(it->queryIdx)], size, color);
1105  }
1106 }
1107 
1108 void vpKeyPoint::display(const vpImage<vpRGBa> &ICurrent, unsigned int size, const vpColor &color)
1109 {
1110  std::vector<vpImagePoint> vpQueryImageKeyPoints;
1111  getQueryKeyPoints(vpQueryImageKeyPoints);
1112 
1113  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1114  vpDisplay::displayCross(ICurrent, vpQueryImageKeyPoints[(size_t)(it->queryIdx)], size, color);
1115  }
1116 }
1117 
1119  unsigned int crossSize, unsigned int lineThickness, const vpColor &color)
1120 {
1121  bool randomColor = (color == vpColor::none);
1122  srand((unsigned int)time(nullptr));
1123  vpColor currentColor = color;
1124 
1125  std::vector<vpImagePoint> queryImageKeyPoints;
1126  getQueryKeyPoints(queryImageKeyPoints);
1127  std::vector<vpImagePoint> trainImageKeyPoints;
1128  getTrainKeyPoints(trainImageKeyPoints);
1129 
1130  vpImagePoint leftPt, rightPt;
1131  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1132  if (randomColor) {
1133  currentColor = vpColor((rand() % 256), (rand() % 256), (rand() % 256));
1134  }
1135 
1136  leftPt = trainImageKeyPoints[(size_t)(it->trainIdx)];
1137  rightPt = vpImagePoint(queryImageKeyPoints[(size_t)(it->queryIdx)].get_i(),
1138  queryImageKeyPoints[(size_t)it->queryIdx].get_j() + IRef.getWidth());
1139  vpDisplay::displayCross(IMatching, leftPt, crossSize, currentColor);
1140  vpDisplay::displayCross(IMatching, rightPt, crossSize, currentColor);
1141  vpDisplay::displayLine(IMatching, leftPt, rightPt, currentColor, lineThickness);
1142  }
1143 }
1144 
1145 void vpKeyPoint::displayMatching(const vpImage<unsigned char> &IRef, vpImage<vpRGBa> &IMatching, unsigned int crossSize,
1146  unsigned int lineThickness, const vpColor &color)
1147 {
1148  bool randomColor = (color == vpColor::none);
1149  srand((unsigned int)time(nullptr));
1150  vpColor currentColor = color;
1151 
1152  std::vector<vpImagePoint> queryImageKeyPoints;
1153  getQueryKeyPoints(queryImageKeyPoints);
1154  std::vector<vpImagePoint> trainImageKeyPoints;
1155  getTrainKeyPoints(trainImageKeyPoints);
1156 
1157  vpImagePoint leftPt, rightPt;
1158  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1159  if (randomColor) {
1160  currentColor = vpColor((rand() % 256), (rand() % 256), (rand() % 256));
1161  }
1162 
1163  leftPt = trainImageKeyPoints[(size_t)(it->trainIdx)];
1164  rightPt = vpImagePoint(queryImageKeyPoints[(size_t)(it->queryIdx)].get_i(),
1165  queryImageKeyPoints[(size_t)it->queryIdx].get_j() + IRef.getWidth());
1166  vpDisplay::displayCross(IMatching, leftPt, crossSize, currentColor);
1167  vpDisplay::displayCross(IMatching, rightPt, crossSize, currentColor);
1168  vpDisplay::displayLine(IMatching, leftPt, rightPt, currentColor, lineThickness);
1169  }
1170 }
1171 
1172 void vpKeyPoint::displayMatching(const vpImage<vpRGBa> &IRef, vpImage<vpRGBa> &IMatching, unsigned int crossSize,
1173  unsigned int lineThickness, const vpColor &color)
1174 {
1175  bool randomColor = (color == vpColor::none);
1176  srand((unsigned int)time(nullptr));
1177  vpColor currentColor = color;
1178 
1179  std::vector<vpImagePoint> queryImageKeyPoints;
1180  getQueryKeyPoints(queryImageKeyPoints);
1181  std::vector<vpImagePoint> trainImageKeyPoints;
1182  getTrainKeyPoints(trainImageKeyPoints);
1183 
1184  vpImagePoint leftPt, rightPt;
1185  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1186  if (randomColor) {
1187  currentColor = vpColor((rand() % 256), (rand() % 256), (rand() % 256));
1188  }
1189 
1190  leftPt = trainImageKeyPoints[(size_t)(it->trainIdx)];
1191  rightPt = vpImagePoint(queryImageKeyPoints[(size_t)(it->queryIdx)].get_i(),
1192  queryImageKeyPoints[(size_t)it->queryIdx].get_j() + IRef.getWidth());
1193  vpDisplay::displayCross(IMatching, leftPt, crossSize, currentColor);
1194  vpDisplay::displayCross(IMatching, rightPt, crossSize, currentColor);
1195  vpDisplay::displayLine(IMatching, leftPt, rightPt, currentColor, lineThickness);
1196  }
1197 }
1198 
1199 
1201  const std::vector<vpImagePoint> &ransacInliers, unsigned int crossSize,
1202  unsigned int lineThickness)
1203 {
1204  if (m_mapOfImages.empty() || m_mapOfImageId.empty()) {
1205  // No training images so return
1206  std::cerr << "There is no training image loaded !" << std::endl;
1207  return;
1208  }
1209 
1210  // Nb images in the training database + the current image we want to detect
1211  // the object
1212  int nbImg = (int)(m_mapOfImages.size() + 1);
1213 
1214  if (nbImg == 2) {
1215  // Only one training image, so we display the matching result side-by-side
1216  displayMatching(m_mapOfImages.begin()->second, IMatching, crossSize);
1217  }
1218  else {
1219  // Multiple training images, display them as a mosaic image
1220  int nbImgSqrt = vpMath::round(std::sqrt((double)nbImg)); //(int) std::floor(std::sqrt((double) nbImg) + 0.5);
1221  int nbWidth = nbImgSqrt;
1222  int nbHeight = nbImgSqrt;
1223 
1224  if (nbImgSqrt * nbImgSqrt < nbImg) {
1225  nbWidth++;
1226  }
1227 
1228  std::map<int, int> mapOfImageIdIndex;
1229  int cpt = 0;
1230  unsigned int maxW = ICurrent.getWidth(), maxH = ICurrent.getHeight();
1231  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
1232  ++it, cpt++) {
1233  mapOfImageIdIndex[it->first] = cpt;
1234 
1235  if (maxW < it->second.getWidth()) {
1236  maxW = it->second.getWidth();
1237  }
1238 
1239  if (maxH < it->second.getHeight()) {
1240  maxH = it->second.getHeight();
1241  }
1242  }
1243 
1244  // Indexes of the current image in the grid computed to put preferably the
1245  // image in the center of the mosaic grid
1246  int medianI = nbHeight / 2;
1247  int medianJ = nbWidth / 2;
1248  int medianIndex = medianI * nbWidth + medianJ;
1249  for (std::vector<cv::KeyPoint>::const_iterator it = m_trainKeyPoints.begin(); it != m_trainKeyPoints.end(); ++it) {
1250  vpImagePoint topLeftCorner;
1251  int current_class_id_index = 0;
1252  if (mapOfImageIdIndex[m_mapOfImageId[it->class_id]] < medianIndex) {
1253  current_class_id_index = mapOfImageIdIndex[m_mapOfImageId[it->class_id]];
1254  }
1255  else {
1256  // Shift of one unity the index of the training images which are after
1257  // the current image
1258  current_class_id_index = mapOfImageIdIndex[m_mapOfImageId[it->class_id]] + 1;
1259  }
1260 
1261  int indexI = current_class_id_index / nbWidth;
1262  int indexJ = current_class_id_index - (indexI * nbWidth);
1263  topLeftCorner.set_ij((int)maxH * indexI, (int)maxW * indexJ);
1264 
1265  // Display cross for keypoints in the learning database
1266  vpDisplay::displayCross(IMatching, (int)(it->pt.y + topLeftCorner.get_i()),
1267  (int)(it->pt.x + topLeftCorner.get_j()), crossSize, vpColor::red);
1268  }
1269 
1270  vpImagePoint topLeftCorner((int)maxH * medianI, (int)maxW * medianJ);
1271  for (std::vector<cv::KeyPoint>::const_iterator it = m_queryKeyPoints.begin(); it != m_queryKeyPoints.end(); ++it) {
1272  // Display cross for keypoints detected in the current image
1273  vpDisplay::displayCross(IMatching, (int)(it->pt.y + topLeftCorner.get_i()),
1274  (int)(it->pt.x + topLeftCorner.get_j()), crossSize, vpColor::red);
1275  }
1276  for (std::vector<vpImagePoint>::const_iterator it = ransacInliers.begin(); it != ransacInliers.end(); ++it) {
1277  // Display green circle for RANSAC inliers
1278  vpDisplay::displayCircle(IMatching, (int)(it->get_v() + topLeftCorner.get_i()),
1279  (int)(it->get_u() + topLeftCorner.get_j()), 4, vpColor::green);
1280  }
1281  for (std::vector<vpImagePoint>::const_iterator it = m_ransacOutliers.begin(); it != m_ransacOutliers.end(); ++it) {
1282  // Display red circle for RANSAC outliers
1283  vpDisplay::displayCircle(IMatching, (int)(it->get_i() + topLeftCorner.get_i()),
1284  (int)(it->get_j() + topLeftCorner.get_j()), 4, vpColor::red);
1285  }
1286 
1287  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1288  int current_class_id = 0;
1289  if (mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]] < medianIndex) {
1290  current_class_id = mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]];
1291  }
1292  else {
1293  // Shift of one unity the index of the training images which are after
1294  // the current image
1295  current_class_id = mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]] + 1;
1296  }
1297 
1298  int indexI = current_class_id / nbWidth;
1299  int indexJ = current_class_id - (indexI * nbWidth);
1300 
1301  vpImagePoint end((int)maxH * indexI + m_trainKeyPoints[(size_t)it->trainIdx].pt.y,
1302  (int)maxW * indexJ + m_trainKeyPoints[(size_t)it->trainIdx].pt.x);
1303  vpImagePoint start((int)maxH * medianI + m_queryFilteredKeyPoints[(size_t)it->queryIdx].pt.y,
1304  (int)maxW * medianJ + m_queryFilteredKeyPoints[(size_t)it->queryIdx].pt.x);
1305 
1306  // Draw line for matching keypoints detected in the current image and
1307  // those detected in the training images
1308  vpDisplay::displayLine(IMatching, start, end, vpColor::green, lineThickness);
1309  }
1310  }
1311 }
1312 
1314  const std::vector<vpImagePoint> &ransacInliers, unsigned int crossSize,
1315  unsigned int lineThickness)
1316 {
1317  if (m_mapOfImages.empty() || m_mapOfImageId.empty()) {
1318  // No training images so return
1319  std::cerr << "There is no training image loaded !" << std::endl;
1320  return;
1321  }
1322 
1323  // Nb images in the training database + the current image we want to detect
1324  // the object
1325  int nbImg = (int)(m_mapOfImages.size() + 1);
1326 
1327  if (nbImg == 2) {
1328  // Only one training image, so we display the matching result side-by-side
1329  displayMatching(m_mapOfImages.begin()->second, IMatching, crossSize);
1330  }
1331  else {
1332  // Multiple training images, display them as a mosaic image
1333  int nbImgSqrt = vpMath::round(std::sqrt((double)nbImg)); //(int) std::floor(std::sqrt((double) nbImg) + 0.5);
1334  int nbWidth = nbImgSqrt;
1335  int nbHeight = nbImgSqrt;
1336 
1337  if (nbImgSqrt * nbImgSqrt < nbImg) {
1338  nbWidth++;
1339  }
1340 
1341  std::map<int, int> mapOfImageIdIndex;
1342  int cpt = 0;
1343  unsigned int maxW = ICurrent.getWidth(), maxH = ICurrent.getHeight();
1344  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
1345  ++it, cpt++) {
1346  mapOfImageIdIndex[it->first] = cpt;
1347 
1348  if (maxW < it->second.getWidth()) {
1349  maxW = it->second.getWidth();
1350  }
1351 
1352  if (maxH < it->second.getHeight()) {
1353  maxH = it->second.getHeight();
1354  }
1355  }
1356 
1357  // Indexes of the current image in the grid computed to put preferably the
1358  // image in the center of the mosaic grid
1359  int medianI = nbHeight / 2;
1360  int medianJ = nbWidth / 2;
1361  int medianIndex = medianI * nbWidth + medianJ;
1362  for (std::vector<cv::KeyPoint>::const_iterator it = m_trainKeyPoints.begin(); it != m_trainKeyPoints.end(); ++it) {
1363  vpImagePoint topLeftCorner;
1364  int current_class_id_index = 0;
1365  if (mapOfImageIdIndex[m_mapOfImageId[it->class_id]] < medianIndex) {
1366  current_class_id_index = mapOfImageIdIndex[m_mapOfImageId[it->class_id]];
1367  }
1368  else {
1369  // Shift of one unity the index of the training images which are after
1370  // the current image
1371  current_class_id_index = mapOfImageIdIndex[m_mapOfImageId[it->class_id]] + 1;
1372  }
1373 
1374  int indexI = current_class_id_index / nbWidth;
1375  int indexJ = current_class_id_index - (indexI * nbWidth);
1376  topLeftCorner.set_ij((int)maxH * indexI, (int)maxW * indexJ);
1377 
1378  // Display cross for keypoints in the learning database
1379  vpDisplay::displayCross(IMatching, (int)(it->pt.y + topLeftCorner.get_i()),
1380  (int)(it->pt.x + topLeftCorner.get_j()), crossSize, vpColor::red);
1381  }
1382 
1383  vpImagePoint topLeftCorner((int)maxH * medianI, (int)maxW * medianJ);
1384  for (std::vector<cv::KeyPoint>::const_iterator it = m_queryKeyPoints.begin(); it != m_queryKeyPoints.end(); ++it) {
1385  // Display cross for keypoints detected in the current image
1386  vpDisplay::displayCross(IMatching, (int)(it->pt.y + topLeftCorner.get_i()),
1387  (int)(it->pt.x + topLeftCorner.get_j()), crossSize, vpColor::red);
1388  }
1389  for (std::vector<vpImagePoint>::const_iterator it = ransacInliers.begin(); it != ransacInliers.end(); ++it) {
1390  // Display green circle for RANSAC inliers
1391  vpDisplay::displayCircle(IMatching, (int)(it->get_v() + topLeftCorner.get_i()),
1392  (int)(it->get_u() + topLeftCorner.get_j()), 4, vpColor::green);
1393  }
1394  for (std::vector<vpImagePoint>::const_iterator it = m_ransacOutliers.begin(); it != m_ransacOutliers.end(); ++it) {
1395  // Display red circle for RANSAC outliers
1396  vpDisplay::displayCircle(IMatching, (int)(it->get_i() + topLeftCorner.get_i()),
1397  (int)(it->get_j() + topLeftCorner.get_j()), 4, vpColor::red);
1398  }
1399 
1400  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
1401  int current_class_id = 0;
1402  if (mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]] < medianIndex) {
1403  current_class_id = mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]];
1404  }
1405  else {
1406  // Shift of one unity the index of the training images which are after
1407  // the current image
1408  current_class_id = mapOfImageIdIndex[m_mapOfImageId[m_trainKeyPoints[(size_t)it->trainIdx].class_id]] + 1;
1409  }
1410 
1411  int indexI = current_class_id / nbWidth;
1412  int indexJ = current_class_id - (indexI * nbWidth);
1413 
1414  vpImagePoint end((int)maxH * indexI + m_trainKeyPoints[(size_t)it->trainIdx].pt.y,
1415  (int)maxW * indexJ + m_trainKeyPoints[(size_t)it->trainIdx].pt.x);
1416  vpImagePoint start((int)maxH * medianI + m_queryFilteredKeyPoints[(size_t)it->queryIdx].pt.y,
1417  (int)maxW * medianJ + m_queryFilteredKeyPoints[(size_t)it->queryIdx].pt.x);
1418 
1419  // Draw line for matching keypoints detected in the current image and
1420  // those detected in the training images
1421  vpDisplay::displayLine(IMatching, start, end, vpColor::green, lineThickness);
1422  }
1423  }
1424 }
1425 
1426 void vpKeyPoint::extract(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
1427  std::vector<cv::Point3f> *trainPoints)
1428 {
1429  double elapsedTime;
1430  extract(I, keyPoints, descriptors, elapsedTime, trainPoints);
1431 }
1432 
1433 void vpKeyPoint::extract(const vpImage<vpRGBa> &I_color, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
1434  std::vector<cv::Point3f> *trainPoints)
1435 {
1436  double elapsedTime;
1437  extract(I_color, keyPoints, descriptors, elapsedTime, trainPoints);
1438 }
1439 
1440 void vpKeyPoint::extract(const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
1441  std::vector<cv::Point3f> *trainPoints)
1442 {
1443  double elapsedTime;
1444  extract(matImg, keyPoints, descriptors, elapsedTime, trainPoints);
1445 }
1446 
1447 void vpKeyPoint::extract(const vpImage<unsigned char> &I, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
1448  double &elapsedTime, std::vector<cv::Point3f> *trainPoints)
1449 {
1450  cv::Mat matImg;
1451  vpImageConvert::convert(I, matImg, false);
1452  extract(matImg, keyPoints, descriptors, elapsedTime, trainPoints);
1453 }
1454 
1455 void vpKeyPoint::extract(const vpImage<vpRGBa> &I_color, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
1456  double &elapsedTime, std::vector<cv::Point3f> *trainPoints)
1457 {
1458  cv::Mat matImg;
1459  vpImageConvert::convert(I_color, matImg);
1460  extract(matImg, keyPoints, descriptors, elapsedTime, trainPoints);
1461 }
1462 
1463 void vpKeyPoint::extract(const cv::Mat &matImg, std::vector<cv::KeyPoint> &keyPoints, cv::Mat &descriptors,
1464  double &elapsedTime, std::vector<cv::Point3f> *trainPoints)
1465 {
1466  double t = vpTime::measureTimeMs();
1467  bool first = true;
1468 
1469  for (std::map<std::string, cv::Ptr<cv::DescriptorExtractor> >::const_iterator itd = m_extractors.begin();
1470  itd != m_extractors.end(); ++itd) {
1471  if (first) {
1472  first = false;
1473  // Check if we have 3D object points information
1474  if (trainPoints != nullptr && !trainPoints->empty()) {
1475  // Copy the input list of keypoints, keypoints that cannot be computed
1476  // are removed in the function compute
1477  std::vector<cv::KeyPoint> keyPoints_tmp = keyPoints;
1478 
1479  // Extract descriptors for the given list of keypoints
1480  itd->second->compute(matImg, keyPoints, descriptors);
1481 
1482  if (keyPoints.size() != keyPoints_tmp.size()) {
1483  // Keypoints have been removed
1484  // Store the hash of a keypoint as the key and the index of the
1485  // keypoint as the value
1486  std::map<size_t, size_t> mapOfKeypointHashes;
1487  size_t cpt = 0;
1488  for (std::vector<cv::KeyPoint>::const_iterator it = keyPoints_tmp.begin(); it != keyPoints_tmp.end();
1489  ++it, cpt++) {
1490  mapOfKeypointHashes[myKeypointHash(*it)] = cpt;
1491  }
1492 
1493  std::vector<cv::Point3f> trainPoints_tmp;
1494  for (std::vector<cv::KeyPoint>::const_iterator it = keyPoints.begin(); it != keyPoints.end(); ++it) {
1495  if (mapOfKeypointHashes.find(myKeypointHash(*it)) != mapOfKeypointHashes.end()) {
1496  trainPoints_tmp.push_back((*trainPoints)[mapOfKeypointHashes[myKeypointHash(*it)]]);
1497  }
1498  }
1499 
1500  // Copy trainPoints_tmp to m_trainPoints
1501  *trainPoints = trainPoints_tmp;
1502  }
1503  }
1504  else {
1505  // Extract descriptors for the given list of keypoints
1506  itd->second->compute(matImg, keyPoints, descriptors);
1507  }
1508  }
1509  else {
1510  // Copy the input list of keypoints, keypoints that cannot be computed
1511  // are removed in the function compute
1512  std::vector<cv::KeyPoint> keyPoints_tmp = keyPoints;
1513 
1514  cv::Mat desc;
1515  // Extract descriptors for the given list of keypoints
1516  itd->second->compute(matImg, keyPoints, desc);
1517 
1518  if (keyPoints.size() != keyPoints_tmp.size()) {
1519  // Keypoints have been removed
1520  // Store the hash of a keypoint as the key and the index of the
1521  // keypoint as the value
1522  std::map<size_t, size_t> mapOfKeypointHashes;
1523  size_t cpt = 0;
1524  for (std::vector<cv::KeyPoint>::const_iterator it = keyPoints_tmp.begin(); it != keyPoints_tmp.end();
1525  ++it, cpt++) {
1526  mapOfKeypointHashes[myKeypointHash(*it)] = cpt;
1527  }
1528 
1529  std::vector<cv::Point3f> trainPoints_tmp;
1530  cv::Mat descriptors_tmp;
1531  for (std::vector<cv::KeyPoint>::const_iterator it = keyPoints.begin(); it != keyPoints.end(); ++it) {
1532  if (mapOfKeypointHashes.find(myKeypointHash(*it)) != mapOfKeypointHashes.end()) {
1533  if (trainPoints != nullptr && !trainPoints->empty()) {
1534  trainPoints_tmp.push_back((*trainPoints)[mapOfKeypointHashes[myKeypointHash(*it)]]);
1535  }
1536 
1537  if (!descriptors.empty()) {
1538  descriptors_tmp.push_back(descriptors.row((int)mapOfKeypointHashes[myKeypointHash(*it)]));
1539  }
1540  }
1541  }
1542 
1543  if (trainPoints != nullptr) {
1544  // Copy trainPoints_tmp to m_trainPoints
1545  *trainPoints = trainPoints_tmp;
1546  }
1547  // Copy descriptors_tmp to descriptors
1548  descriptors_tmp.copyTo(descriptors);
1549  }
1550 
1551  // Merge descriptors horizontally
1552  if (descriptors.empty()) {
1553  desc.copyTo(descriptors);
1554  }
1555  else {
1556  cv::hconcat(descriptors, desc, descriptors);
1557  }
1558  }
1559  }
1560 
1561  if (keyPoints.size() != (size_t)descriptors.rows) {
1562  std::cerr << "keyPoints.size() != (size_t) descriptors.rows" << std::endl;
1563  }
1564  elapsedTime = vpTime::measureTimeMs() - t;
1565 }
1566 
1567 void vpKeyPoint::filterMatches()
1568 {
1569  std::vector<cv::KeyPoint> queryKpts;
1570  std::vector<cv::Point3f> trainPts;
1571  std::vector<cv::DMatch> m;
1572 
1573  if (m_useKnn) {
1574  // double max_dist = 0;
1575  // double min_dist = std::numeric_limits<double>::max(); // create an
1576  // error under Windows. To fix it we have to add #undef max
1577  double min_dist = DBL_MAX;
1578  double mean = 0.0;
1579  std::vector<double> distance_vec(m_knnMatches.size());
1580 
1581  if (m_filterType == stdAndRatioDistanceThreshold) {
1582  for (size_t i = 0; i < m_knnMatches.size(); i++) {
1583  double dist = m_knnMatches[i][0].distance;
1584  mean += dist;
1585  distance_vec[i] = dist;
1586 
1587  if (dist < min_dist) {
1588  min_dist = dist;
1589  }
1590  // if (dist > max_dist) {
1591  // max_dist = dist;
1592  //}
1593  }
1594  mean /= m_queryDescriptors.rows;
1595  }
1596 
1597  double sq_sum = std::inner_product(distance_vec.begin(), distance_vec.end(), distance_vec.begin(), 0.0);
1598  double stdev = std::sqrt(sq_sum / distance_vec.size() - mean * mean);
1599  double threshold = min_dist + stdev;
1600 
1601  for (size_t i = 0; i < m_knnMatches.size(); i++) {
1602  if (m_knnMatches[i].size() >= 2) {
1603  // Calculate ratio of the descriptor distance between the two nearest
1604  // neighbors of the keypoint
1605  float ratio = m_knnMatches[i][0].distance / m_knnMatches[i][1].distance;
1606  // float ratio = std::sqrt((vecMatches[i][0].distance *
1607  // vecMatches[i][0].distance)
1608  // / (vecMatches[i][1].distance *
1609  // vecMatches[i][1].distance));
1610  double dist = m_knnMatches[i][0].distance;
1611 
1612  if (ratio < m_matchingRatioThreshold || (m_filterType == stdAndRatioDistanceThreshold && dist < threshold)) {
1613  m.push_back(cv::DMatch((int)queryKpts.size(), m_knnMatches[i][0].trainIdx, m_knnMatches[i][0].distance));
1614 
1615  if (!m_trainPoints.empty()) {
1616  trainPts.push_back(m_trainPoints[(size_t)m_knnMatches[i][0].trainIdx]);
1617  }
1618  queryKpts.push_back(m_queryKeyPoints[(size_t)m_knnMatches[i][0].queryIdx]);
1619  }
1620  }
1621  }
1622  }
1623  else {
1624  // double max_dist = 0;
1625  // create an error under Windows. To fix it we have to add #undef max
1626  // double min_dist = std::numeric_limits<double>::max();
1627  double min_dist = DBL_MAX;
1628  double mean = 0.0;
1629  std::vector<double> distance_vec(m_matches.size());
1630  for (size_t i = 0; i < m_matches.size(); i++) {
1631  double dist = m_matches[i].distance;
1632  mean += dist;
1633  distance_vec[i] = dist;
1634 
1635  if (dist < min_dist) {
1636  min_dist = dist;
1637  }
1638  // if (dist > max_dist) {
1639  // max_dist = dist;
1640  // }
1641  }
1642  mean /= m_queryDescriptors.rows;
1643 
1644  double sq_sum = std::inner_product(distance_vec.begin(), distance_vec.end(), distance_vec.begin(), 0.0);
1645  double stdev = std::sqrt(sq_sum / distance_vec.size() - mean * mean);
1646 
1647  // Define a threshold where we keep all keypoints whose the descriptor
1648  // distance falls below a factor of the minimum descriptor distance (for
1649  // all the query keypoints) or below the minimum descriptor distance +
1650  // the standard deviation (calculated on all the query descriptor
1651  // distances)
1652  double threshold =
1653  m_filterType == constantFactorDistanceThreshold ? m_matchingFactorThreshold * min_dist : min_dist + stdev;
1654 
1655  for (size_t i = 0; i < m_matches.size(); i++) {
1656  if (m_matches[i].distance <= threshold) {
1657  m.push_back(cv::DMatch((int)queryKpts.size(), m_matches[i].trainIdx, m_matches[i].distance));
1658 
1659  if (!m_trainPoints.empty()) {
1660  trainPts.push_back(m_trainPoints[(size_t)m_matches[i].trainIdx]);
1661  }
1662  queryKpts.push_back(m_queryKeyPoints[(size_t)m_matches[i].queryIdx]);
1663  }
1664  }
1665  }
1666 
1667  if (m_useSingleMatchFilter) {
1668  // Eliminate matches where multiple query keypoints are matched to the
1669  // same train keypoint
1670  std::vector<cv::DMatch> mTmp;
1671  std::vector<cv::Point3f> trainPtsTmp;
1672  std::vector<cv::KeyPoint> queryKptsTmp;
1673 
1674  std::map<int, int> mapOfTrainIdx;
1675  // Count the number of query points matched to the same train point
1676  for (std::vector<cv::DMatch>::const_iterator it = m.begin(); it != m.end(); ++it) {
1677  mapOfTrainIdx[it->trainIdx]++;
1678  }
1679 
1680  // Keep matches with only one correspondence
1681  for (std::vector<cv::DMatch>::const_iterator it = m.begin(); it != m.end(); ++it) {
1682  if (mapOfTrainIdx[it->trainIdx] == 1) {
1683  mTmp.push_back(cv::DMatch((int)queryKptsTmp.size(), it->trainIdx, it->distance));
1684 
1685  if (!m_trainPoints.empty()) {
1686  trainPtsTmp.push_back(m_trainPoints[(size_t)it->trainIdx]);
1687  }
1688  queryKptsTmp.push_back(queryKpts[(size_t)it->queryIdx]);
1689  }
1690  }
1691 
1692  m_filteredMatches = mTmp;
1693  m_objectFilteredPoints = trainPtsTmp;
1694  m_queryFilteredKeyPoints = queryKptsTmp;
1695  }
1696  else {
1697  m_filteredMatches = m;
1698  m_objectFilteredPoints = trainPts;
1699  m_queryFilteredKeyPoints = queryKpts;
1700  }
1701 }
1702 
1703 void vpKeyPoint::getObjectPoints(std::vector<cv::Point3f> &objectPoints) const
1704 {
1705  objectPoints = m_objectFilteredPoints;
1706 }
1707 
1708 void vpKeyPoint::getObjectPoints(std::vector<vpPoint> &objectPoints) const
1709 {
1710  vpConvert::convertFromOpenCV(m_objectFilteredPoints, objectPoints);
1711 }
1712 
1713 void vpKeyPoint::getQueryKeyPoints(std::vector<cv::KeyPoint> &keyPoints, bool matches) const
1714 {
1715  if (matches) {
1716  keyPoints = m_queryFilteredKeyPoints;
1717  }
1718  else {
1719  keyPoints = m_queryKeyPoints;
1720  }
1721 }
1722 
1723 void vpKeyPoint::getQueryKeyPoints(std::vector<vpImagePoint> &keyPoints, bool matches) const
1724 {
1725  if (matches) {
1726  keyPoints = m_currentImagePointsList;
1727  }
1728  else {
1729  vpConvert::convertFromOpenCV(m_queryKeyPoints, keyPoints);
1730  }
1731 }
1732 
1733 void vpKeyPoint::getTrainKeyPoints(std::vector<cv::KeyPoint> &keyPoints) const { keyPoints = m_trainKeyPoints; }
1734 
1735 void vpKeyPoint::getTrainKeyPoints(std::vector<vpImagePoint> &keyPoints) const { keyPoints = m_referenceImagePointsList; }
1736 
1737 void vpKeyPoint::getTrainPoints(std::vector<cv::Point3f> &points) const { points = m_trainPoints; }
1738 
1739 void vpKeyPoint::getTrainPoints(std::vector<vpPoint> &points) const { points = m_trainVpPoints; }
1740 
1741 void vpKeyPoint::init()
1742 {
1743 // Require 2.4.0 <= opencv < 3.0.0
1744 #if defined(HAVE_OPENCV_NONFREE) && (VISP_HAVE_OPENCV_VERSION >= 0x020400) && (VISP_HAVE_OPENCV_VERSION < 0x030000)
1745  // The following line must be called in order to use SIFT or SURF
1746  if (!cv::initModule_nonfree()) {
1747  std::cerr << "Cannot init module non free, SURF cannot be used." << std::endl;
1748  }
1749 #endif
1750 
1751  // Use k-nearest neighbors (knn) to retrieve the two best matches for a
1752  // keypoint So this is useful only for ratioDistanceThreshold method
1753  if (m_filterType == ratioDistanceThreshold || m_filterType == stdAndRatioDistanceThreshold) {
1754  m_useKnn = true;
1755  }
1756 
1757  initDetectors(m_detectorNames);
1758  initExtractors(m_extractorNames);
1759  initMatcher(m_matcherName);
1760 }
1761 
1762 void vpKeyPoint::initDetector(const std::string &detectorName)
1763 {
1764 #if (VISP_HAVE_OPENCV_VERSION < 0x030000)
1765  m_detectors[detectorName] = cv::FeatureDetector::create(detectorName);
1766 
1767  if (m_detectors[detectorName] == nullptr) {
1768  std::stringstream ss_msg;
1769  ss_msg << "Fail to initialize the detector: " << detectorName
1770  << " or it is not available in OpenCV version: " << std::hex << VISP_HAVE_OPENCV_VERSION << ".";
1771  throw vpException(vpException::fatalError, ss_msg.str());
1772  }
1773 #else
1774  std::string detectorNameTmp = detectorName;
1775  std::string pyramid = "Pyramid";
1776  std::size_t pos = detectorName.find(pyramid);
1777  bool usePyramid = false;
1778  if (pos != std::string::npos) {
1779  detectorNameTmp = detectorName.substr(pos + pyramid.size());
1780  usePyramid = true;
1781  }
1782 
1783  if (detectorNameTmp == "SIFT") {
1784 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && ((VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)) && defined(HAVE_OPENCV_FEATURES2D)) \
1785  || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
1786 # if (VISP_HAVE_OPENCV_VERSION >= 0x040500) // OpenCV >= 4.5.0
1787  cv::Ptr<cv::FeatureDetector> siftDetector = cv::SiftFeatureDetector::create();
1788  if (!usePyramid) {
1789  m_detectors[detectorNameTmp] = siftDetector;
1790  }
1791  else {
1792  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(siftDetector);
1793  }
1794 # elif (VISP_HAVE_OPENCV_VERSION >= 0x030411)
1795  // SIFT is no more patented since 09/03/2020
1796  cv::Ptr<cv::FeatureDetector> siftDetector;
1797  if (m_maxFeatures > 0) {
1798  siftDetector = cv::SIFT::create(m_maxFeatures);
1799  }
1800  else {
1801  siftDetector = cv::SIFT::create();
1802  }
1803 # else
1804  cv::Ptr<cv::FeatureDetector> siftDetector;
1805  siftDetector = cv::xfeatures2d::SIFT::create();
1806 # endif
1807  if (!usePyramid) {
1808  m_detectors[detectorNameTmp] = siftDetector;
1809  }
1810  else {
1811  std::cerr << "You should not use SIFT with Pyramid feature detection!" << std::endl;
1812  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(siftDetector);
1813  }
1814 # else
1815  std::stringstream ss_msg;
1816  ss_msg << "Failed to initialize the SIFT 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1817  throw vpException(vpException::fatalError, ss_msg.str());
1818 #endif
1819  }
1820  else if (detectorNameTmp == "SURF") {
1821 #if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D)
1822  cv::Ptr<cv::FeatureDetector> surfDetector = cv::xfeatures2d::SURF::create();
1823  if (!usePyramid) {
1824  m_detectors[detectorNameTmp] = surfDetector;
1825  }
1826  else {
1827  std::cerr << "You should not use SURF with Pyramid feature detection!" << std::endl;
1828  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(surfDetector);
1829  }
1830 #else
1831  std::stringstream ss_msg;
1832  ss_msg << "Failed to initialize the SURF 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1833  throw vpException(vpException::fatalError, ss_msg.str());
1834 #endif
1835  }
1836  else if (detectorNameTmp == "FAST") {
1837 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
1838  cv::Ptr<cv::FeatureDetector> fastDetector = cv::FastFeatureDetector::create();
1839  if (!usePyramid) {
1840  m_detectors[detectorNameTmp] = fastDetector;
1841  }
1842  else {
1843  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(fastDetector);
1844  }
1845 #else
1846  std::stringstream ss_msg;
1847  ss_msg << "Failed to initialize the FAST 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1848  throw vpException(vpException::fatalError, ss_msg.str());
1849 #endif
1850  }
1851  else if (detectorNameTmp == "MSER") {
1852 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
1853  cv::Ptr<cv::FeatureDetector> fastDetector = cv::MSER::create();
1854  if (!usePyramid) {
1855  m_detectors[detectorNameTmp] = fastDetector;
1856  }
1857  else {
1858  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(fastDetector);
1859  }
1860 #else
1861  std::stringstream ss_msg;
1862  ss_msg << "Failed to initialize the MSER 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1863  throw vpException(vpException::fatalError, ss_msg.str());
1864 #endif
1865  }
1866  else if (detectorNameTmp == "ORB") {
1867 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
1868  cv::Ptr<cv::FeatureDetector> orbDetector;
1869  if (m_maxFeatures > 0) {
1870  orbDetector = cv::ORB::create(m_maxFeatures);
1871  }
1872  else {
1873  orbDetector = cv::ORB::create();
1874  }
1875  if (!usePyramid) {
1876  m_detectors[detectorNameTmp] = orbDetector;
1877  }
1878  else {
1879  std::cerr << "You should not use ORB with Pyramid feature detection!" << std::endl;
1880  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(orbDetector);
1881  }
1882 #else
1883  std::stringstream ss_msg;
1884  ss_msg << "Failed to initialize the ORB 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1885  throw vpException(vpException::fatalError, ss_msg.str());
1886 #endif
1887  }
1888  else if (detectorNameTmp == "BRISK") {
1889 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
1890 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
1891  cv::Ptr<cv::FeatureDetector> briskDetector = cv::xfeatures2d::BRISK::create();
1892 #else
1893  cv::Ptr<cv::FeatureDetector> briskDetector = cv::BRISK::create();
1894 #endif
1895  if (!usePyramid) {
1896  m_detectors[detectorNameTmp] = briskDetector;
1897  }
1898  else {
1899  std::cerr << "You should not use BRISK with Pyramid feature detection!" << std::endl;
1900  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(briskDetector);
1901  }
1902 #else
1903  std::stringstream ss_msg;
1904 
1905  ss_msg << "Failed to initialize the BRISK 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1906  throw vpException(vpException::fatalError, ss_msg.str());
1907 #endif
1908  }
1909  else if (detectorNameTmp == "KAZE") {
1910 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
1911 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
1912  cv::Ptr<cv::FeatureDetector> kazeDetector = cv::xfeatures2d::KAZE::create();
1913 #else
1914  cv::Ptr<cv::FeatureDetector> kazeDetector = cv::KAZE::create();
1915 #endif
1916  if (!usePyramid) {
1917  m_detectors[detectorNameTmp] = kazeDetector;
1918  }
1919  else {
1920  std::cerr << "You should not use KAZE with Pyramid feature detection!" << std::endl;
1921  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(kazeDetector);
1922  }
1923 #else
1924  std::stringstream ss_msg;
1925  ss_msg << "Failed to initialize the KAZE 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1926  throw vpException(vpException::fatalError, ss_msg.str());
1927 #endif
1928  }
1929  else if (detectorNameTmp == "AKAZE") {
1930 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
1931 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
1932  cv::Ptr<cv::FeatureDetector> akazeDetector = cv::xfeatures2d::AKAZE::create();
1933 #else
1934  cv::Ptr<cv::FeatureDetector> akazeDetector = cv::AKAZE::create();
1935 #endif
1936  if (!usePyramid) {
1937  m_detectors[detectorNameTmp] = akazeDetector;
1938  }
1939  else {
1940  std::cerr << "You should not use AKAZE with Pyramid feature detection!" << std::endl;
1941  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(akazeDetector);
1942  }
1943 #else
1944  std::stringstream ss_msg;
1945  ss_msg << "Failed to initialize the AKAZE 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1946  throw vpException(vpException::fatalError, ss_msg.str());
1947 #endif
1948  }
1949  else if (detectorNameTmp == "GFTT") {
1950 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
1951  cv::Ptr<cv::FeatureDetector> gfttDetector = cv::GFTTDetector::create();
1952  if (!usePyramid) {
1953  m_detectors[detectorNameTmp] = gfttDetector;
1954  }
1955  else {
1956  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(gfttDetector);
1957  }
1958 #else
1959  std::stringstream ss_msg;
1960  ss_msg << "Failed to initialize the GFTT 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1961  throw vpException(vpException::fatalError, ss_msg.str());
1962 #endif
1963  }
1964  else if (detectorNameTmp == "SimpleBlob") {
1965 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
1966  cv::Ptr<cv::FeatureDetector> simpleBlobDetector = cv::SimpleBlobDetector::create();
1967  if (!usePyramid) {
1968  m_detectors[detectorNameTmp] = simpleBlobDetector;
1969  }
1970  else {
1971  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(simpleBlobDetector);
1972  }
1973 #else
1974  std::stringstream ss_msg;
1975  ss_msg << "Failed to initialize the SimpleBlob 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1976  throw vpException(vpException::fatalError, ss_msg.str());
1977 #endif
1978  }
1979  else if (detectorNameTmp == "STAR") {
1980 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined(VISP_HAVE_OPENCV_XFEATURES2D))) \
1981  || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
1982  cv::Ptr<cv::FeatureDetector> starDetector = cv::xfeatures2d::StarDetector::create();
1983  if (!usePyramid) {
1984  m_detectors[detectorNameTmp] = starDetector;
1985  }
1986  else {
1987  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(starDetector);
1988  }
1989 #else
1990  std::stringstream ss_msg;
1991  ss_msg << "Failed to initialize the STAR 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
1992  throw vpException(vpException::fatalError, ss_msg.str());
1993 #endif
1994  }
1995  else if (detectorNameTmp == "AGAST") {
1996 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
1997 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
1998  cv::Ptr<cv::FeatureDetector> agastDetector = cv::xfeatures2d::AgastFeatureDetector::create();
1999 #else
2000  cv::Ptr<cv::FeatureDetector> agastDetector = cv::AgastFeatureDetector::create();
2001 #endif
2002  if (!usePyramid) {
2003  m_detectors[detectorNameTmp] = agastDetector;
2004  }
2005  else {
2006  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(agastDetector);
2007  }
2008 #else
2009  std::stringstream ss_msg;
2010  ss_msg << "Failed to initialize the STAR 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2011  throw vpException(vpException::fatalError, ss_msg.str());
2012 #endif
2013  }
2014  else if (detectorNameTmp == "MSD") {
2015 #if (VISP_HAVE_OPENCV_VERSION >= 0x030100) && defined(VISP_HAVE_OPENCV_XFEATURES2D)
2016  cv::Ptr<cv::FeatureDetector> msdDetector = cv::xfeatures2d::MSDDetector::create();
2017  if (!usePyramid) {
2018  m_detectors[detectorNameTmp] = msdDetector;
2019  }
2020  else {
2021  std::cerr << "You should not use MSD with Pyramid feature detection!" << std::endl;
2022  m_detectors[detectorName] = cv::makePtr<PyramidAdaptedFeatureDetector>(msdDetector);
2023  }
2024 #else
2025  std::stringstream ss_msg;
2026  ss_msg << "Failed to initialize the MSD 2D features detector with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2027  throw vpException(vpException::fatalError, ss_msg.str());
2028 #endif
2029  }
2030  else {
2031  std::cerr << "The detector:" << detectorNameTmp << " is not available." << std::endl;
2032  }
2033 
2034  bool detectorInitialized = false;
2035  if (!usePyramid) {
2036  // if not null and to avoid warning C4800: forcing value to bool 'true' or 'false' (performance warning)
2037  detectorInitialized = !m_detectors[detectorNameTmp].empty();
2038  }
2039  else {
2040  // if not null and to avoid warning C4800: forcing value to bool 'true' or 'false' (performance warning)
2041  detectorInitialized = !m_detectors[detectorName].empty();
2042  }
2043 
2044  if (!detectorInitialized) {
2045  std::stringstream ss_msg;
2046  ss_msg << "Fail to initialize the detector: " << detectorNameTmp
2047  << " or it is not available in OpenCV version: " << std::hex << VISP_HAVE_OPENCV_VERSION << ".";
2048  throw vpException(vpException::fatalError, ss_msg.str());
2049  }
2050 #endif
2051 }
2052 
2053 void vpKeyPoint::initDetectors(const std::vector<std::string> &detectorNames)
2054 {
2055  for (std::vector<std::string>::const_iterator it = detectorNames.begin(); it != detectorNames.end(); ++it) {
2056  initDetector(*it);
2057  }
2058 }
2059 
2060 void vpKeyPoint::initExtractor(const std::string &extractorName)
2061 {
2062 #if (VISP_HAVE_OPENCV_VERSION < 0x030000)
2063  m_extractors[extractorName] = cv::DescriptorExtractor::create(extractorName);
2064 #else
2065  if (extractorName == "SIFT") {
2066 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && ((VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
2067  // SIFT is no more patented since 09/03/2020
2068 # if (VISP_HAVE_OPENCV_VERSION >= 0x030411)
2069  m_extractors[extractorName] = cv::SIFT::create();
2070 # else
2071  m_extractors[extractorName] = cv::xfeatures2d::SIFT::create();
2072 # endif
2073 #else
2074  std::stringstream ss_msg;
2075  ss_msg << "Fail to initialize the SIFT 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2076  throw vpException(vpException::fatalError, ss_msg.str());
2077 #endif
2078  }
2079  else if (extractorName == "SURF") {
2080 #if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D)
2081  // Use extended set of SURF descriptors (128 instead of 64)
2082  m_extractors[extractorName] = cv::xfeatures2d::SURF::create(100, 4, 3, true);
2083 #else
2084  std::stringstream ss_msg;
2085  ss_msg << "Fail to initialize the SURF 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2086  throw vpException(vpException::fatalError, ss_msg.str());
2087 #endif
2088  }
2089  else if (extractorName == "ORB") {
2090 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
2091  m_extractors[extractorName] = cv::ORB::create();
2092 #else
2093  std::stringstream ss_msg;
2094  ss_msg << "Fail to initialize the ORB 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2095  throw vpException(vpException::fatalError, ss_msg.str());
2096 #endif
2097  }
2098  else if (extractorName == "BRISK") {
2099 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
2100 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
2101  m_extractors[extractorName] = cv::xfeatures2d::BRISK::create();
2102 #else
2103  m_extractors[extractorName] = cv::BRISK::create();
2104 #endif
2105 #else
2106  std::stringstream ss_msg;
2107  ss_msg << "Fail to initialize the BRISK 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2108  throw vpException(vpException::fatalError, ss_msg.str());
2109 #endif
2110  }
2111  else if (extractorName == "FREAK") {
2112 #if defined(HAVE_OPENCV_XFEATURES2D)
2113  m_extractors[extractorName] = cv::xfeatures2d::FREAK::create();
2114 #else
2115  std::stringstream ss_msg;
2116  ss_msg << "Fail to initialize the FREAK 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2117  throw vpException(vpException::fatalError, ss_msg.str());
2118 #endif
2119  }
2120  else if (extractorName == "BRIEF") {
2121 #if defined(HAVE_OPENCV_XFEATURES2D)
2122  m_extractors[extractorName] = cv::xfeatures2d::BriefDescriptorExtractor::create();
2123 #else
2124  std::stringstream ss_msg;
2125  ss_msg << "Fail to initialize the BRIEF 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2126  throw vpException(vpException::fatalError, ss_msg.str());
2127 #endif
2128  }
2129  else if (extractorName == "KAZE") {
2130 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
2131 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
2132  m_extractors[extractorName] = cv::xfeatures2d::KAZE::create();
2133 #else
2134  m_extractors[extractorName] = cv::KAZE::create();
2135 #endif
2136 #else
2137  std::stringstream ss_msg;
2138  ss_msg << "Fail to initialize the KAZE 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2139  throw vpException(vpException::fatalError, ss_msg.str());
2140 #endif
2141  }
2142  else if (extractorName == "AKAZE") {
2143 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
2144 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
2145  m_extractors[extractorName] = cv::xfeatures2d::AKAZE::create();
2146 #else
2147  m_extractors[extractorName] = cv::AKAZE::create();
2148 #endif
2149 #else
2150  std::stringstream ss_msg;
2151  ss_msg << "Fail to initialize the AKAZE 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2152  throw vpException(vpException::fatalError, ss_msg.str());
2153 #endif
2154  }
2155  else if (extractorName == "DAISY") {
2156 #if defined(HAVE_OPENCV_XFEATURES2D)
2157  m_extractors[extractorName] = cv::xfeatures2d::DAISY::create();
2158 #else
2159  std::stringstream ss_msg;
2160  ss_msg << "Fail to initialize the DAISY 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2161  throw vpException(vpException::fatalError, ss_msg.str());
2162 #endif
2163  }
2164  else if (extractorName == "LATCH") {
2165 #if defined(HAVE_OPENCV_XFEATURES2D)
2166  m_extractors[extractorName] = cv::xfeatures2d::LATCH::create();
2167 #else
2168  std::stringstream ss_msg;
2169  ss_msg << "Fail to initialize the LATCH 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2170  throw vpException(vpException::fatalError, ss_msg.str());
2171 #endif
2172  }
2173  else if (extractorName == "VGG") {
2174 #if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D)
2175  m_extractors[extractorName] = cv::xfeatures2d::VGG::create();
2176 #else
2177  std::stringstream ss_msg;
2178  ss_msg << "Fail to initialize the VGG 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2179  throw vpException(vpException::fatalError, ss_msg.str());
2180 #endif
2181  }
2182  else if (extractorName == "BoostDesc") {
2183 #if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D)
2184  m_extractors[extractorName] = cv::xfeatures2d::BoostDesc::create();
2185 #else
2186  std::stringstream ss_msg;
2187  ss_msg << "Fail to initialize the BoostDesc 2D features extractor with OpenCV version " << std::hex << VISP_HAVE_OPENCV_VERSION;
2188  throw vpException(vpException::fatalError, ss_msg.str());
2189 #endif
2190  }
2191  else {
2192  std::cerr << "The extractor:" << extractorName << " is not available." << std::endl;
2193  }
2194 #endif
2195 
2196  if (!m_extractors[extractorName]) { // if null
2197  std::stringstream ss_msg;
2198  ss_msg << "Fail to initialize the extractor: " << extractorName
2199  << " or it is not available in OpenCV version: " << std::hex << VISP_HAVE_OPENCV_VERSION << ".";
2200  throw vpException(vpException::fatalError, ss_msg.str());
2201  }
2202 
2203 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
2204  if (extractorName == "SURF") {
2205  // Use extended set of SURF descriptors (128 instead of 64)
2206  m_extractors[extractorName]->set("extended", 1);
2207  }
2208 #endif
2209 }
2210 
2211 void vpKeyPoint::initExtractors(const std::vector<std::string> &extractorNames)
2212 {
2213  for (std::vector<std::string>::const_iterator it = extractorNames.begin(); it != extractorNames.end(); ++it) {
2214  initExtractor(*it);
2215  }
2216 
2217  int descriptorType = CV_32F;
2218  bool firstIteration = true;
2219  for (std::map<std::string, cv::Ptr<cv::DescriptorExtractor> >::const_iterator it = m_extractors.begin();
2220  it != m_extractors.end(); ++it) {
2221  if (firstIteration) {
2222  firstIteration = false;
2223  descriptorType = it->second->descriptorType();
2224  }
2225  else {
2226  if (descriptorType != it->second->descriptorType()) {
2227  throw vpException(vpException::fatalError, "All the descriptors must have the same type !");
2228  }
2229  }
2230  }
2231 }
2232 
2233 void vpKeyPoint::initFeatureNames()
2234 {
2235 // Create map enum to string
2236 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
2237  m_mapOfDetectorNames[DETECTOR_FAST] = "FAST";
2238  m_mapOfDetectorNames[DETECTOR_MSER] = "MSER";
2239  m_mapOfDetectorNames[DETECTOR_ORB] = "ORB";
2240  m_mapOfDetectorNames[DETECTOR_GFTT] = "GFTT";
2241  m_mapOfDetectorNames[DETECTOR_SimpleBlob] = "SimpleBlob";
2242 #endif
2243 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
2244  m_mapOfDetectorNames[DETECTOR_BRISK] = "BRISK";
2245 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
2246  m_mapOfDetectorNames[DETECTOR_KAZE] = "KAZE";
2247  m_mapOfDetectorNames[DETECTOR_AKAZE] = "AKAZE";
2248  m_mapOfDetectorNames[DETECTOR_AGAST] = "AGAST";
2249 #endif
2250 #endif
2251 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && (VISP_HAVE_OPENCV_VERSION < 0x030000) || (defined(VISP_HAVE_OPENCV_XFEATURES2D))) \
2252  || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
2253  m_mapOfDetectorNames[DETECTOR_STAR] = "STAR";
2254 #endif
2255 #if (VISP_HAVE_OPENCV_VERSION >= 0x030100) && defined(VISP_HAVE_OPENCV_XFEATURES2D)
2256  m_mapOfDetectorNames[DETECTOR_MSD] = "MSD";
2257 #endif
2258 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && ((VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)) && defined(HAVE_OPENCV_FEATURES2D)) \
2259  || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
2260  m_mapOfDetectorNames[DETECTOR_SIFT] = "SIFT";
2261 #endif
2262 #if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D)
2263  m_mapOfDetectorNames[DETECTOR_SURF] = "SURF";
2264 #endif
2265 
2266 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
2267  m_mapOfDescriptorNames[DESCRIPTOR_ORB] = "ORB";
2268 #endif
2269 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
2270  m_mapOfDescriptorNames[DESCRIPTOR_BRISK] = "BRISK";
2271 #endif
2272 #if defined(VISP_HAVE_OPENCV_XFEATURES2D)
2273  m_mapOfDescriptorNames[DESCRIPTOR_BRIEF] = "BRIEF";
2274  m_mapOfDescriptorNames[DESCRIPTOR_FREAK] = "FREAK";
2275 #endif
2276 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && ((VISP_HAVE_OPENCV_VERSION >= 0x030411 && CV_MAJOR_VERSION < 4) || (VISP_HAVE_OPENCV_VERSION >= 0x040400)) && defined(HAVE_OPENCV_FEATURES2D)) \
2277  || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_FEATURES))
2278  m_mapOfDescriptorNames[DESCRIPTOR_SIFT] = "SIFT";
2279 #endif
2280 #if defined(OPENCV_ENABLE_NONFREE) && defined(HAVE_OPENCV_XFEATURES2D)
2281  m_mapOfDescriptorNames[DESCRIPTOR_SURF] = "SURF";
2282 #endif
2283 #if ((VISP_HAVE_OPENCV_VERSION < 0x050000) && defined(HAVE_OPENCV_FEATURES2D)) || ((VISP_HAVE_OPENCV_VERSION >= 0x050000) && defined(HAVE_OPENCV_XFEATURES2D))
2284 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
2285  m_mapOfDescriptorNames[DESCRIPTOR_KAZE] = "KAZE";
2286  m_mapOfDescriptorNames[DESCRIPTOR_AKAZE] = "AKAZE";
2287 #endif
2288 #endif
2289 #if defined(HAVE_OPENCV_XFEATURES2D)
2290  m_mapOfDescriptorNames[DESCRIPTOR_DAISY] = "DAISY";
2291  m_mapOfDescriptorNames[DESCRIPTOR_LATCH] = "LATCH";
2292 #endif
2293 #if (VISP_HAVE_OPENCV_VERSION >= 0x030200) && defined(HAVE_OPENCV_XFEATURES2D)
2294  m_mapOfDescriptorNames[DESCRIPTOR_VGG] = "VGG";
2295  m_mapOfDescriptorNames[DESCRIPTOR_BoostDesc] = "BoostDesc";
2296 #endif
2297 }
2298 
2299 void vpKeyPoint::initMatcher(const std::string &matcherName)
2300 {
2301  int descriptorType = CV_32F;
2302  bool firstIteration = true;
2303  for (std::map<std::string, cv::Ptr<cv::DescriptorExtractor> >::const_iterator it = m_extractors.begin();
2304  it != m_extractors.end(); ++it) {
2305  if (firstIteration) {
2306  firstIteration = false;
2307  descriptorType = it->second->descriptorType();
2308  }
2309  else {
2310  if (descriptorType != it->second->descriptorType()) {
2311  throw vpException(vpException::fatalError, "All the descriptors must have the same type !");
2312  }
2313  }
2314  }
2315 
2316  if (matcherName == "FlannBased") {
2317  if (m_extractors.empty()) {
2318  std::cout << "Warning: No extractor initialized, by default use "
2319  "floating values (CV_32F) "
2320  "for descriptor type !"
2321  << std::endl;
2322  }
2323 
2324  if (descriptorType == CV_8U) {
2325 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
2326  m_matcher = cv::makePtr<cv::FlannBasedMatcher>(cv::makePtr<cv::flann::LshIndexParams>(12, 20, 2));
2327 #else
2328  m_matcher = new cv::FlannBasedMatcher(new cv::flann::LshIndexParams(12, 20, 2));
2329 #endif
2330  }
2331  else {
2332 #if (VISP_HAVE_OPENCV_VERSION >= 0x030000)
2333  m_matcher = cv::makePtr<cv::FlannBasedMatcher>(cv::makePtr<cv::flann::KDTreeIndexParams>());
2334 #else
2335  m_matcher = new cv::FlannBasedMatcher(new cv::flann::KDTreeIndexParams());
2336 #endif
2337  }
2338  }
2339  else {
2340  m_matcher = cv::DescriptorMatcher::create(matcherName);
2341  }
2342 
2343 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
2344  if (m_matcher != nullptr && !m_useKnn && matcherName == "BruteForce") {
2345  m_matcher->set("crossCheck", m_useBruteForceCrossCheck);
2346  }
2347 #endif
2348 
2349  if (!m_matcher) { // if null
2350  std::stringstream ss_msg;
2351  ss_msg << "Fail to initialize the matcher: " << matcherName
2352  << " or it is not available in OpenCV version: " << std::hex << VISP_HAVE_OPENCV_VERSION << ".";
2353  throw vpException(vpException::fatalError, ss_msg.str());
2354  }
2355 }
2356 
2358  vpImage<unsigned char> &IMatching)
2359 {
2360  vpImagePoint topLeftCorner(0, 0);
2361  IMatching.insert(IRef, topLeftCorner);
2362  topLeftCorner = vpImagePoint(0, IRef.getWidth());
2363  IMatching.insert(ICurrent, topLeftCorner);
2364 }
2365 
2367  vpImage<vpRGBa> &IMatching)
2368 {
2369  vpImagePoint topLeftCorner(0, 0);
2370  IMatching.insert(IRef, topLeftCorner);
2371  topLeftCorner = vpImagePoint(0, IRef.getWidth());
2372  IMatching.insert(ICurrent, topLeftCorner);
2373 }
2374 
2376 {
2377  // Nb images in the training database + the current image we want to detect
2378  // the object
2379  int nbImg = (int)(m_mapOfImages.size() + 1);
2380 
2381  if (m_mapOfImages.empty()) {
2382  std::cerr << "There is no training image loaded !" << std::endl;
2383  return;
2384  }
2385 
2386  if (nbImg == 2) {
2387  // Only one training image, so we display them side by side
2388  insertImageMatching(m_mapOfImages.begin()->second, ICurrent, IMatching);
2389  }
2390  else {
2391  // Multiple training images, display them as a mosaic image
2392  int nbImgSqrt = vpMath::round(std::sqrt((double)nbImg)); //(int) std::floor(std::sqrt((double) nbImg) + 0.5);
2393  int nbWidth = nbImgSqrt;
2394  int nbHeight = nbImgSqrt;
2395 
2396  if (nbImgSqrt * nbImgSqrt < nbImg) {
2397  nbWidth++;
2398  }
2399 
2400  unsigned int maxW = ICurrent.getWidth(), maxH = ICurrent.getHeight();
2401  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
2402  ++it) {
2403  if (maxW < it->second.getWidth()) {
2404  maxW = it->second.getWidth();
2405  }
2406 
2407  if (maxH < it->second.getHeight()) {
2408  maxH = it->second.getHeight();
2409  }
2410  }
2411 
2412  // Indexes of the current image in the grid made in order to the image is
2413  // in the center square in the mosaic grid
2414  int medianI = nbHeight / 2;
2415  int medianJ = nbWidth / 2;
2416  int medianIndex = medianI * nbWidth + medianJ;
2417 
2418  int cpt = 0;
2419  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
2420  ++it, cpt++) {
2421  int local_cpt = cpt;
2422  if (cpt >= medianIndex) {
2423  // Shift of one unity the index of the training images which are after
2424  // the current image
2425  local_cpt++;
2426  }
2427  int indexI = local_cpt / nbWidth;
2428  int indexJ = local_cpt - (indexI * nbWidth);
2429  vpImagePoint topLeftCorner((int)maxH * indexI, (int)maxW * indexJ);
2430 
2431  IMatching.insert(it->second, topLeftCorner);
2432  }
2433 
2434  vpImagePoint topLeftCorner((int)maxH * medianI, (int)maxW * medianJ);
2435  IMatching.insert(ICurrent, topLeftCorner);
2436  }
2437 }
2438 
2440 {
2441  // Nb images in the training database + the current image we want to detect
2442  // the object
2443  int nbImg = (int)(m_mapOfImages.size() + 1);
2444 
2445  if (m_mapOfImages.empty()) {
2446  std::cerr << "There is no training image loaded !" << std::endl;
2447  return;
2448  }
2449 
2450  if (nbImg == 2) {
2451  // Only one training image, so we display them side by side
2452  vpImage<vpRGBa> IRef;
2453  vpImageConvert::convert(m_mapOfImages.begin()->second, IRef);
2454  insertImageMatching(IRef, ICurrent, IMatching);
2455  }
2456  else {
2457  // Multiple training images, display them as a mosaic image
2458  int nbImgSqrt = vpMath::round(std::sqrt((double)nbImg)); //(int) std::floor(std::sqrt((double) nbImg) + 0.5);
2459  int nbWidth = nbImgSqrt;
2460  int nbHeight = nbImgSqrt;
2461 
2462  if (nbImgSqrt * nbImgSqrt < nbImg) {
2463  nbWidth++;
2464  }
2465 
2466  unsigned int maxW = ICurrent.getWidth(), maxH = ICurrent.getHeight();
2467  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
2468  ++it) {
2469  if (maxW < it->second.getWidth()) {
2470  maxW = it->second.getWidth();
2471  }
2472 
2473  if (maxH < it->second.getHeight()) {
2474  maxH = it->second.getHeight();
2475  }
2476  }
2477 
2478  // Indexes of the current image in the grid made in order to the image is
2479  // in the center square in the mosaic grid
2480  int medianI = nbHeight / 2;
2481  int medianJ = nbWidth / 2;
2482  int medianIndex = medianI * nbWidth + medianJ;
2483 
2484  int cpt = 0;
2485  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
2486  ++it, cpt++) {
2487  int local_cpt = cpt;
2488  if (cpt >= medianIndex) {
2489  // Shift of one unity the index of the training images which are after
2490  // the current image
2491  local_cpt++;
2492  }
2493  int indexI = local_cpt / nbWidth;
2494  int indexJ = local_cpt - (indexI * nbWidth);
2495  vpImagePoint topLeftCorner((int)maxH * indexI, (int)maxW * indexJ);
2496 
2497  vpImage<vpRGBa> IRef;
2498  vpImageConvert::convert(it->second, IRef);
2499  IMatching.insert(IRef, topLeftCorner);
2500  }
2501 
2502  vpImagePoint topLeftCorner((int)maxH * medianI, (int)maxW * medianJ);
2503  IMatching.insert(ICurrent, topLeftCorner);
2504  }
2505 }
2506 
2507 void vpKeyPoint::loadConfigFile(const std::string &configFile)
2508 {
2509 #if defined(VISP_HAVE_PUGIXML)
2511 
2512  try {
2513  // Reset detector and extractor
2514  m_detectorNames.clear();
2515  m_extractorNames.clear();
2516  m_detectors.clear();
2517  m_extractors.clear();
2518 
2519  std::cout << " *********** Parsing XML for configuration for vpKeyPoint "
2520  "************ "
2521  << std::endl;
2522  xmlp.parse(configFile);
2523 
2524  m_detectorNames.push_back(xmlp.getDetectorName());
2525  m_extractorNames.push_back(xmlp.getExtractorName());
2526  m_matcherName = xmlp.getMatcherName();
2527 
2528  switch (xmlp.getMatchingMethod()) {
2530  m_filterType = constantFactorDistanceThreshold;
2531  break;
2532 
2534  m_filterType = stdDistanceThreshold;
2535  break;
2536 
2538  m_filterType = ratioDistanceThreshold;
2539  break;
2540 
2542  m_filterType = stdAndRatioDistanceThreshold;
2543  break;
2544 
2546  m_filterType = noFilterMatching;
2547  break;
2548 
2549  default:
2550  break;
2551  }
2552 
2553  m_matchingFactorThreshold = xmlp.getMatchingFactorThreshold();
2554  m_matchingRatioThreshold = xmlp.getMatchingRatioThreshold();
2555 
2556  m_useRansacVVS = xmlp.getUseRansacVVSPoseEstimation();
2557  m_useConsensusPercentage = xmlp.getUseRansacConsensusPercentage();
2558  m_nbRansacIterations = xmlp.getNbRansacIterations();
2559  m_ransacReprojectionError = xmlp.getRansacReprojectionError();
2560  m_nbRansacMinInlierCount = xmlp.getNbRansacMinInlierCount();
2561  m_ransacThreshold = xmlp.getRansacThreshold();
2562  m_ransacConsensusPercentage = xmlp.getRansacConsensusPercentage();
2563 
2564  if (m_filterType == ratioDistanceThreshold || m_filterType == stdAndRatioDistanceThreshold) {
2565  m_useKnn = true;
2566  }
2567  else {
2568  m_useKnn = false;
2569  }
2570 
2571  init();
2572  }
2573  catch (...) {
2574  throw vpException(vpException::ioError, "Can't open XML file \"%s\"\n ", configFile.c_str());
2575  }
2576 #else
2577  (void)configFile;
2578  throw vpException(vpException::ioError, "vpKeyPoint::loadConfigFile() in xml needs built-in pugixml 3rdparty that is not available");
2579 #endif
2580 }
2581 
2582 void vpKeyPoint::loadLearningData(const std::string &filename, bool binaryMode, bool append)
2583 {
2584  int startClassId = 0;
2585  int startImageId = 0;
2586  if (!append) {
2587  m_trainKeyPoints.clear();
2588  m_trainPoints.clear();
2589  m_mapOfImageId.clear();
2590  m_mapOfImages.clear();
2591  }
2592  else {
2593  // In append case, find the max index of keypoint class Id
2594  for (std::map<int, int>::const_iterator it = m_mapOfImageId.begin(); it != m_mapOfImageId.end(); ++it) {
2595  if (startClassId < it->first) {
2596  startClassId = it->first;
2597  }
2598  }
2599 
2600  // In append case, find the max index of images Id
2601  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
2602  ++it) {
2603  if (startImageId < it->first) {
2604  startImageId = it->first;
2605  }
2606  }
2607  }
2608 
2609  // Get parent directory
2610  std::string parent = vpIoTools::getParent(filename);
2611  if (!parent.empty()) {
2612  parent += "/";
2613  }
2614 
2615  if (binaryMode) {
2616  std::ifstream file(filename.c_str(), std::ifstream::binary);
2617  if (!file.is_open()) {
2618  throw vpException(vpException::ioError, "Cannot open the file.");
2619  }
2620 
2621  // Read info about training images
2622  int nbImgs = 0;
2623  vpIoTools::readBinaryValueLE(file, nbImgs);
2624 
2625 #if !defined(VISP_HAVE_MODULE_IO)
2626  if (nbImgs > 0) {
2627  std::cout << "Warning: The learning file contains image data that will "
2628  "not be loaded as visp_io module "
2629  "is not available !"
2630  << std::endl;
2631  }
2632 #endif
2633 
2634  for (int i = 0; i < nbImgs; i++) {
2635  // Read image_id
2636  int id = 0;
2637  vpIoTools::readBinaryValueLE(file, id);
2638 
2639  int length = 0;
2640  vpIoTools::readBinaryValueLE(file, length);
2641  // Will contain the path to the training images
2642  char *path = new char[length + 1]; // char path[length + 1];
2643 
2644  for (int cpt = 0; cpt < length; cpt++) {
2645  char c;
2646  file.read((char *)(&c), sizeof(c));
2647  path[cpt] = c;
2648  }
2649  path[length] = '\0';
2650 
2652 #ifdef VISP_HAVE_MODULE_IO
2653  if (vpIoTools::isAbsolutePathname(std::string(path))) {
2654  vpImageIo::read(I, path);
2655  }
2656  else {
2657  vpImageIo::read(I, parent + path);
2658  }
2659 
2660  // Add the image previously loaded only if VISP_HAVE_MODULE_IO
2661  m_mapOfImages[id + startImageId] = I;
2662 #endif
2663 
2664  // Delete path
2665  delete[] path;
2666  }
2667 
2668  // Read if 3D point information are saved or not
2669  int have3DInfoInt = 0;
2670  vpIoTools::readBinaryValueLE(file, have3DInfoInt);
2671  bool have3DInfo = have3DInfoInt != 0;
2672 
2673  // Read the number of descriptors
2674  int nRows = 0;
2675  vpIoTools::readBinaryValueLE(file, nRows);
2676 
2677  // Read the size of the descriptor
2678  int nCols = 0;
2679  vpIoTools::readBinaryValueLE(file, nCols);
2680 
2681  // Read the type of the descriptor
2682  int descriptorType = 5; // CV_32F
2683  vpIoTools::readBinaryValueLE(file, descriptorType);
2684 
2685  cv::Mat trainDescriptorsTmp = cv::Mat(nRows, nCols, descriptorType);
2686  for (int i = 0; i < nRows; i++) {
2687  // Read information about keyPoint
2688  float u, v, size, angle, response;
2689  int octave, class_id, image_id;
2692  vpIoTools::readBinaryValueLE(file, size);
2693  vpIoTools::readBinaryValueLE(file, angle);
2694  vpIoTools::readBinaryValueLE(file, response);
2695  vpIoTools::readBinaryValueLE(file, octave);
2696  vpIoTools::readBinaryValueLE(file, class_id);
2697  vpIoTools::readBinaryValueLE(file, image_id);
2698  cv::KeyPoint keyPoint(cv::Point2f(u, v), size, angle, response, octave, (class_id + startClassId));
2699  m_trainKeyPoints.push_back(keyPoint);
2700 
2701  if (image_id != -1) {
2702 #ifdef VISP_HAVE_MODULE_IO
2703  // No training images if image_id == -1
2704  m_mapOfImageId[m_trainKeyPoints.back().class_id] = image_id + startImageId;
2705 #endif
2706  }
2707 
2708  if (have3DInfo) {
2709  // Read oX, oY, oZ
2710  float oX, oY, oZ;
2711  vpIoTools::readBinaryValueLE(file, oX);
2712  vpIoTools::readBinaryValueLE(file, oY);
2713  vpIoTools::readBinaryValueLE(file, oZ);
2714  m_trainPoints.push_back(cv::Point3f(oX, oY, oZ));
2715  }
2716 
2717  for (int j = 0; j < nCols; j++) {
2718  // Read the value of the descriptor
2719  switch (descriptorType) {
2720  case CV_8U: {
2721  unsigned char value;
2722  file.read((char *)(&value), sizeof(value));
2723  trainDescriptorsTmp.at<unsigned char>(i, j) = value;
2724  } break;
2725 
2726  case CV_8S: {
2727  char value;
2728  file.read((char *)(&value), sizeof(value));
2729  trainDescriptorsTmp.at<char>(i, j) = value;
2730  } break;
2731 
2732  case CV_16U: {
2733  unsigned short int value;
2734  vpIoTools::readBinaryValueLE(file, value);
2735  trainDescriptorsTmp.at<unsigned short int>(i, j) = value;
2736  } break;
2737 
2738  case CV_16S: {
2739  short int value;
2740  vpIoTools::readBinaryValueLE(file, value);
2741  trainDescriptorsTmp.at<short int>(i, j) = value;
2742  } break;
2743 
2744  case CV_32S: {
2745  int value;
2746  vpIoTools::readBinaryValueLE(file, value);
2747  trainDescriptorsTmp.at<int>(i, j) = value;
2748  } break;
2749 
2750  case CV_32F: {
2751  float value;
2752  vpIoTools::readBinaryValueLE(file, value);
2753  trainDescriptorsTmp.at<float>(i, j) = value;
2754  } break;
2755 
2756  case CV_64F: {
2757  double value;
2758  vpIoTools::readBinaryValueLE(file, value);
2759  trainDescriptorsTmp.at<double>(i, j) = value;
2760  } break;
2761 
2762  default: {
2763  float value;
2764  vpIoTools::readBinaryValueLE(file, value);
2765  trainDescriptorsTmp.at<float>(i, j) = value;
2766  } break;
2767  }
2768  }
2769  }
2770 
2771  if (!append || m_trainDescriptors.empty()) {
2772  trainDescriptorsTmp.copyTo(m_trainDescriptors);
2773  }
2774  else {
2775  cv::vconcat(m_trainDescriptors, trainDescriptorsTmp, m_trainDescriptors);
2776  }
2777 
2778  file.close();
2779  }
2780  else {
2781 #if defined(VISP_HAVE_PUGIXML)
2782  pugi::xml_document doc;
2783 
2784  /*parse the file and get the DOM */
2785  if (!doc.load_file(filename.c_str())) {
2786  throw vpException(vpException::ioError, "Error with file: %s", filename.c_str());
2787  }
2788 
2789  pugi::xml_node root_element = doc.document_element();
2790 
2791  int descriptorType = CV_32F; // float
2792  int nRows = 0, nCols = 0;
2793  int i = 0, j = 0;
2794 
2795  cv::Mat trainDescriptorsTmp;
2796 
2797  for (pugi::xml_node first_level_node = root_element.first_child(); first_level_node;
2798  first_level_node = first_level_node.next_sibling()) {
2799 
2800  std::string name(first_level_node.name());
2801  if (first_level_node.type() == pugi::node_element && name == "TrainingImageInfo") {
2802 
2803  for (pugi::xml_node image_info_node = first_level_node.first_child(); image_info_node;
2804  image_info_node = image_info_node.next_sibling()) {
2805  name = std::string(image_info_node.name());
2806 
2807  if (name == "trainImg") {
2808  // Read image_id
2809  int id = image_info_node.attribute("image_id").as_int();
2810 
2812 #ifdef VISP_HAVE_MODULE_IO
2813  std::string path(image_info_node.text().as_string());
2814  // Read path to the training images
2815  if (vpIoTools::isAbsolutePathname(std::string(path))) {
2816  vpImageIo::read(I, path);
2817  }
2818  else {
2819  vpImageIo::read(I, parent + path);
2820  }
2821 
2822  // Add the image previously loaded only if VISP_HAVE_MODULE_IO
2823  m_mapOfImages[id + startImageId] = I;
2824 #endif
2825  }
2826  }
2827  }
2828  else if (first_level_node.type() == pugi::node_element && name == "DescriptorsInfo") {
2829  for (pugi::xml_node descriptors_info_node = first_level_node.first_child(); descriptors_info_node;
2830  descriptors_info_node = descriptors_info_node.next_sibling()) {
2831  if (descriptors_info_node.type() == pugi::node_element) {
2832  name = std::string(descriptors_info_node.name());
2833 
2834  if (name == "nrows") {
2835  nRows = descriptors_info_node.text().as_int();
2836  }
2837  else if (name == "ncols") {
2838  nCols = descriptors_info_node.text().as_int();
2839  }
2840  else if (name == "type") {
2841  descriptorType = descriptors_info_node.text().as_int();
2842  }
2843  }
2844  }
2845 
2846  trainDescriptorsTmp = cv::Mat(nRows, nCols, descriptorType);
2847  }
2848  else if (first_level_node.type() == pugi::node_element && name == "DescriptorInfo") {
2849  double u = 0.0, v = 0.0, size = 0.0, angle = 0.0, response = 0.0;
2850  int octave = 0, class_id = 0, image_id = 0;
2851  double oX = 0.0, oY = 0.0, oZ = 0.0;
2852 
2853  std::stringstream ss;
2854 
2855  for (pugi::xml_node point_node = first_level_node.first_child(); point_node;
2856  point_node = point_node.next_sibling()) {
2857  if (point_node.type() == pugi::node_element) {
2858  name = std::string(point_node.name());
2859 
2860  // Read information about keypoints
2861  if (name == "u") {
2862  u = point_node.text().as_double();
2863  }
2864  else if (name == "v") {
2865  v = point_node.text().as_double();
2866  }
2867  else if (name == "size") {
2868  size = point_node.text().as_double();
2869  }
2870  else if (name == "angle") {
2871  angle = point_node.text().as_double();
2872  }
2873  else if (name == "response") {
2874  response = point_node.text().as_double();
2875  }
2876  else if (name == "octave") {
2877  octave = point_node.text().as_int();
2878  }
2879  else if (name == "class_id") {
2880  class_id = point_node.text().as_int();
2881  cv::KeyPoint keyPoint(cv::Point2f((float)u, (float)v), (float)size, (float)angle, (float)response, octave,
2882  (class_id + startClassId));
2883  m_trainKeyPoints.push_back(keyPoint);
2884  }
2885  else if (name == "image_id") {
2886  image_id = point_node.text().as_int();
2887  if (image_id != -1) {
2888 #ifdef VISP_HAVE_MODULE_IO
2889  // No training images if image_id == -1
2890  m_mapOfImageId[m_trainKeyPoints.back().class_id] = image_id + startImageId;
2891 #endif
2892  }
2893  }
2894  else if (name == "oX") {
2895  oX = point_node.text().as_double();
2896  }
2897  else if (name == "oY") {
2898  oY = point_node.text().as_double();
2899  }
2900  else if (name == "oZ") {
2901  oZ = point_node.text().as_double();
2902  m_trainPoints.push_back(cv::Point3f((float)oX, (float)oY, (float)oZ));
2903  }
2904  else if (name == "desc") {
2905  j = 0;
2906 
2907  for (pugi::xml_node descriptor_value_node = point_node.first_child(); descriptor_value_node;
2908  descriptor_value_node = descriptor_value_node.next_sibling()) {
2909 
2910  if (descriptor_value_node.type() == pugi::node_element) {
2911  // Read descriptors values
2912  std::string parseStr(descriptor_value_node.text().as_string());
2913  ss.clear();
2914  ss.str(parseStr);
2915 
2916  if (!ss.fail()) {
2917  switch (descriptorType) {
2918  case CV_8U: {
2919  // Parse the numeric value [0 ; 255] to an int
2920  int parseValue;
2921  ss >> parseValue;
2922  trainDescriptorsTmp.at<unsigned char>(i, j) = (unsigned char)parseValue;
2923  } break;
2924 
2925  case CV_8S:
2926  // Parse the numeric value [-128 ; 127] to an int
2927  int parseValue;
2928  ss >> parseValue;
2929  trainDescriptorsTmp.at<char>(i, j) = (char)parseValue;
2930  break;
2931 
2932  case CV_16U:
2933  ss >> trainDescriptorsTmp.at<unsigned short int>(i, j);
2934  break;
2935 
2936  case CV_16S:
2937  ss >> trainDescriptorsTmp.at<short int>(i, j);
2938  break;
2939 
2940  case CV_32S:
2941  ss >> trainDescriptorsTmp.at<int>(i, j);
2942  break;
2943 
2944  case CV_32F:
2945  ss >> trainDescriptorsTmp.at<float>(i, j);
2946  break;
2947 
2948  case CV_64F:
2949  ss >> trainDescriptorsTmp.at<double>(i, j);
2950  break;
2951 
2952  default:
2953  ss >> trainDescriptorsTmp.at<float>(i, j);
2954  break;
2955  }
2956  }
2957  else {
2958  std::cerr << "Error when converting:" << ss.str() << std::endl;
2959  }
2960 
2961  j++;
2962  }
2963  }
2964  }
2965  }
2966  }
2967  i++;
2968  }
2969  }
2970 
2971  if (!append || m_trainDescriptors.empty()) {
2972  trainDescriptorsTmp.copyTo(m_trainDescriptors);
2973  }
2974  else {
2975  cv::vconcat(m_trainDescriptors, trainDescriptorsTmp, m_trainDescriptors);
2976  }
2977 #else
2978  throw vpException(vpException::ioError, "vpKeyPoint::loadLearningData() in xml needs built-in pugixml 3rdparty that is not available");
2979 #endif
2980  }
2981 
2982  // Convert OpenCV type to ViSP type for compatibility
2984  vpConvert::convertFromOpenCV(this->m_trainPoints, m_trainVpPoints);
2985 
2986  // Add train descriptors in matcher object
2987  m_matcher->clear();
2988  m_matcher->add(std::vector<cv::Mat>(1, m_trainDescriptors));
2989 
2990  // Set m_reference_computed to true as we load a learning file
2991  m_reference_computed = true;
2992 
2993  // Set m_currentImageId
2994  m_currentImageId = (int)m_mapOfImages.size();
2995 }
2996 
2997 void vpKeyPoint::match(const cv::Mat &trainDescriptors, const cv::Mat &queryDescriptors,
2998  std::vector<cv::DMatch> &matches, double &elapsedTime)
2999 {
3000  double t = vpTime::measureTimeMs();
3001 
3002  if (m_useKnn) {
3003  m_knnMatches.clear();
3004 
3005  if (m_useMatchTrainToQuery) {
3006  std::vector<std::vector<cv::DMatch> > knnMatchesTmp;
3007 
3008  // Match train descriptors to query descriptors
3009  cv::Ptr<cv::DescriptorMatcher> matcherTmp = m_matcher->clone(true);
3010  matcherTmp->knnMatch(trainDescriptors, queryDescriptors, knnMatchesTmp, 2);
3011 
3012  for (std::vector<std::vector<cv::DMatch> >::const_iterator it1 = knnMatchesTmp.begin();
3013  it1 != knnMatchesTmp.end(); ++it1) {
3014  std::vector<cv::DMatch> tmp;
3015  for (std::vector<cv::DMatch>::const_iterator it2 = it1->begin(); it2 != it1->end(); ++it2) {
3016  tmp.push_back(cv::DMatch(it2->trainIdx, it2->queryIdx, it2->distance));
3017  }
3018  m_knnMatches.push_back(tmp);
3019  }
3020 
3021  matches.resize(m_knnMatches.size());
3022  std::transform(m_knnMatches.begin(), m_knnMatches.end(), matches.begin(), knnToDMatch);
3023  }
3024  else {
3025  // Match query descriptors to train descriptors
3026  m_matcher->knnMatch(queryDescriptors, m_knnMatches, 2);
3027  matches.resize(m_knnMatches.size());
3028  std::transform(m_knnMatches.begin(), m_knnMatches.end(), matches.begin(), knnToDMatch);
3029  }
3030  }
3031  else {
3032  matches.clear();
3033 
3034  if (m_useMatchTrainToQuery) {
3035  std::vector<cv::DMatch> matchesTmp;
3036  // Match train descriptors to query descriptors
3037  cv::Ptr<cv::DescriptorMatcher> matcherTmp = m_matcher->clone(true);
3038  matcherTmp->match(trainDescriptors, queryDescriptors, matchesTmp);
3039 
3040  for (std::vector<cv::DMatch>::const_iterator it = matchesTmp.begin(); it != matchesTmp.end(); ++it) {
3041  matches.push_back(cv::DMatch(it->trainIdx, it->queryIdx, it->distance));
3042  }
3043  }
3044  else {
3045  // Match query descriptors to train descriptors
3046  m_matcher->match(queryDescriptors, matches);
3047  }
3048  }
3049  elapsedTime = vpTime::measureTimeMs() - t;
3050 }
3051 
3052 unsigned int vpKeyPoint::matchPoint(const vpImage<unsigned char> &I) { return matchPoint(I, vpRect()); }
3053 
3054 unsigned int vpKeyPoint::matchPoint(const vpImage<vpRGBa> &I_color) { return matchPoint(I_color, vpRect()); }
3055 
3056 unsigned int vpKeyPoint::matchPoint(const vpImage<unsigned char> &I, const vpImagePoint &iP, unsigned int height,
3057  unsigned int width)
3058 {
3059  return matchPoint(I, vpRect(iP, width, height));
3060 }
3061 
3062 unsigned int vpKeyPoint::matchPoint(const vpImage<vpRGBa> &I_color, const vpImagePoint &iP, unsigned int height,
3063  unsigned int width)
3064 {
3065  return matchPoint(I_color, vpRect(iP, width, height));
3066 }
3067 
3068 unsigned int vpKeyPoint::matchPoint(const vpImage<unsigned char> &I, const vpRect &rectangle)
3069 {
3070  if (m_trainDescriptors.empty()) {
3071  std::cerr << "Reference is empty." << std::endl;
3072  if (!m_reference_computed) {
3073  std::cerr << "Reference is not computed." << std::endl;
3074  }
3075  std::cerr << "Matching is not possible." << std::endl;
3076 
3077  return 0;
3078  }
3079 
3080  if (m_useAffineDetection) {
3081  std::vector<std::vector<cv::KeyPoint> > listOfQueryKeyPoints;
3082  std::vector<cv::Mat> listOfQueryDescriptors;
3083 
3084  // Detect keypoints and extract descriptors on multiple images
3085  detectExtractAffine(I, listOfQueryKeyPoints, listOfQueryDescriptors);
3086 
3087  // Flatten the different train lists
3088  m_queryKeyPoints.clear();
3089  for (std::vector<std::vector<cv::KeyPoint> >::const_iterator it = listOfQueryKeyPoints.begin();
3090  it != listOfQueryKeyPoints.end(); ++it) {
3091  m_queryKeyPoints.insert(m_queryKeyPoints.end(), it->begin(), it->end());
3092  }
3093 
3094  bool first = true;
3095  for (std::vector<cv::Mat>::const_iterator it = listOfQueryDescriptors.begin(); it != listOfQueryDescriptors.end();
3096  ++it) {
3097  if (first) {
3098  first = false;
3099  it->copyTo(m_queryDescriptors);
3100  }
3101  else {
3102  m_queryDescriptors.push_back(*it);
3103  }
3104  }
3105  }
3106  else {
3107  detect(I, m_queryKeyPoints, m_detectionTime, rectangle);
3108  extract(I, m_queryKeyPoints, m_queryDescriptors, m_extractionTime);
3109  }
3110 
3111  return matchPoint(m_queryKeyPoints, m_queryDescriptors);
3112 }
3113 
3114 unsigned int vpKeyPoint::matchPoint(const std::vector<cv::KeyPoint> &queryKeyPoints, const cv::Mat &queryDescriptors)
3115 {
3116  m_queryKeyPoints = queryKeyPoints;
3117  m_queryDescriptors = queryDescriptors;
3118 
3119  match(m_trainDescriptors, m_queryDescriptors, m_matches, m_matchingTime);
3120 
3121  if (m_filterType != noFilterMatching) {
3122  m_queryFilteredKeyPoints.clear();
3123  m_objectFilteredPoints.clear();
3124  m_filteredMatches.clear();
3125 
3126  filterMatches();
3127  }
3128  else {
3129  if (m_useMatchTrainToQuery) {
3130  // Add only query keypoints matched with a train keypoints
3131  m_queryFilteredKeyPoints.clear();
3132  m_filteredMatches.clear();
3133  for (std::vector<cv::DMatch>::const_iterator it = m_matches.begin(); it != m_matches.end(); ++it) {
3134  m_filteredMatches.push_back(cv::DMatch((int)m_queryFilteredKeyPoints.size(), it->trainIdx, it->distance));
3135  m_queryFilteredKeyPoints.push_back(m_queryKeyPoints[(size_t)it->queryIdx]);
3136  }
3137  }
3138  else {
3139  m_queryFilteredKeyPoints = m_queryKeyPoints;
3140  m_filteredMatches = m_matches;
3141  }
3142 
3143  if (!m_trainPoints.empty()) {
3144  m_objectFilteredPoints.clear();
3145  // Add 3D object points such as the same index in
3146  // m_queryFilteredKeyPoints and in m_objectFilteredPoints
3147  // matches to the same train object
3148  for (std::vector<cv::DMatch>::const_iterator it = m_matches.begin(); it != m_matches.end(); ++it) {
3149  // m_matches is normally ordered following the queryDescriptor index
3150  m_objectFilteredPoints.push_back(m_trainPoints[(size_t)it->trainIdx]);
3151  }
3152  }
3153  }
3154 
3155  // Convert OpenCV type to ViSP type for compatibility
3156  vpConvert::convertFromOpenCV(m_queryFilteredKeyPoints, m_currentImagePointsList);
3158 
3159  return static_cast<unsigned int>(m_filteredMatches.size());
3160 }
3161 
3162 unsigned int vpKeyPoint::matchPoint(const vpImage<vpRGBa> &I_color, const vpRect &rectangle)
3163 {
3164  vpImageConvert::convert(I_color, m_I);
3165  return matchPoint(m_I, rectangle);
3166 }
3167 
3169  bool (*func)(const vpHomogeneousMatrix &), const vpRect &rectangle)
3170 {
3171  double error, elapsedTime;
3172  return matchPoint(I, cam, cMo, error, elapsedTime, func, rectangle);
3173 }
3174 
3176  bool (*func)(const vpHomogeneousMatrix &), const vpRect &rectangle)
3177 {
3178  double error, elapsedTime;
3179  return matchPoint(I_color, cam, cMo, error, elapsedTime, func, rectangle);
3180 }
3181 
3183  double &error, double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &),
3184  const vpRect &rectangle)
3185 {
3186  // Check if we have training descriptors
3187  if (m_trainDescriptors.empty()) {
3188  std::cerr << "Reference is empty." << std::endl;
3189  if (!m_reference_computed) {
3190  std::cerr << "Reference is not computed." << std::endl;
3191  }
3192  std::cerr << "Matching is not possible." << std::endl;
3193 
3194  return false;
3195  }
3196 
3197  if (m_useAffineDetection) {
3198  std::vector<std::vector<cv::KeyPoint> > listOfQueryKeyPoints;
3199  std::vector<cv::Mat> listOfQueryDescriptors;
3200 
3201  // Detect keypoints and extract descriptors on multiple images
3202  detectExtractAffine(I, listOfQueryKeyPoints, listOfQueryDescriptors);
3203 
3204  // Flatten the different train lists
3205  m_queryKeyPoints.clear();
3206  for (std::vector<std::vector<cv::KeyPoint> >::const_iterator it = listOfQueryKeyPoints.begin();
3207  it != listOfQueryKeyPoints.end(); ++it) {
3208  m_queryKeyPoints.insert(m_queryKeyPoints.end(), it->begin(), it->end());
3209  }
3210 
3211  bool first = true;
3212  for (std::vector<cv::Mat>::const_iterator it = listOfQueryDescriptors.begin(); it != listOfQueryDescriptors.end();
3213  ++it) {
3214  if (first) {
3215  first = false;
3216  it->copyTo(m_queryDescriptors);
3217  }
3218  else {
3219  m_queryDescriptors.push_back(*it);
3220  }
3221  }
3222  }
3223  else {
3224  detect(I, m_queryKeyPoints, m_detectionTime, rectangle);
3225  extract(I, m_queryKeyPoints, m_queryDescriptors, m_extractionTime);
3226  }
3227 
3228  match(m_trainDescriptors, m_queryDescriptors, m_matches, m_matchingTime);
3229 
3230  elapsedTime = m_detectionTime + m_extractionTime + m_matchingTime;
3231 
3232  if (m_filterType != noFilterMatching) {
3233  m_queryFilteredKeyPoints.clear();
3234  m_objectFilteredPoints.clear();
3235  m_filteredMatches.clear();
3236 
3237  filterMatches();
3238  }
3239  else {
3240  if (m_useMatchTrainToQuery) {
3241  // Add only query keypoints matched with a train keypoints
3242  m_queryFilteredKeyPoints.clear();
3243  m_filteredMatches.clear();
3244  for (std::vector<cv::DMatch>::const_iterator it = m_matches.begin(); it != m_matches.end(); ++it) {
3245  m_filteredMatches.push_back(cv::DMatch((int)m_queryFilteredKeyPoints.size(), it->trainIdx, it->distance));
3246  m_queryFilteredKeyPoints.push_back(m_queryKeyPoints[(size_t)it->queryIdx]);
3247  }
3248  }
3249  else {
3250  m_queryFilteredKeyPoints = m_queryKeyPoints;
3251  m_filteredMatches = m_matches;
3252  }
3253 
3254  if (!m_trainPoints.empty()) {
3255  m_objectFilteredPoints.clear();
3256  // Add 3D object points such as the same index in
3257  // m_queryFilteredKeyPoints and in m_objectFilteredPoints
3258  // matches to the same train object
3259  for (std::vector<cv::DMatch>::const_iterator it = m_matches.begin(); it != m_matches.end(); ++it) {
3260  // m_matches is normally ordered following the queryDescriptor index
3261  m_objectFilteredPoints.push_back(m_trainPoints[(size_t)it->trainIdx]);
3262  }
3263  }
3264  }
3265 
3266  // Convert OpenCV type to ViSP type for compatibility
3267  vpConvert::convertFromOpenCV(m_queryFilteredKeyPoints, m_currentImagePointsList);
3269 
3270  // error = std::numeric_limits<double>::max(); // create an error under
3271  // Windows. To fix it we have to add #undef max
3272  error = DBL_MAX;
3273  m_ransacInliers.clear();
3274  m_ransacOutliers.clear();
3275 
3276  if (m_useRansacVVS) {
3277  std::vector<vpPoint> objectVpPoints(m_objectFilteredPoints.size());
3278  size_t cpt = 0;
3279  // Create a list of vpPoint with 2D coordinates (current keypoint
3280  // location) + 3D coordinates (world/object coordinates)
3281  for (std::vector<cv::Point3f>::const_iterator it = m_objectFilteredPoints.begin();
3282  it != m_objectFilteredPoints.end(); ++it, cpt++) {
3283  vpPoint pt;
3284  pt.setWorldCoordinates(it->x, it->y, it->z);
3285 
3286  vpImagePoint imP(m_queryFilteredKeyPoints[cpt].pt.y, m_queryFilteredKeyPoints[cpt].pt.x);
3287 
3288  double x = 0.0, y = 0.0;
3289  vpPixelMeterConversion::convertPoint(cam, imP, x, y);
3290  pt.set_x(x);
3291  pt.set_y(y);
3292 
3293  objectVpPoints[cpt] = pt;
3294  }
3295 
3296  std::vector<vpPoint> inliers;
3297  std::vector<unsigned int> inlierIndex;
3298 
3299  bool res = computePose(objectVpPoints, cMo, inliers, inlierIndex, m_poseTime, func);
3300 
3301  std::map<unsigned int, bool> mapOfInlierIndex;
3302  m_matchRansacKeyPointsToPoints.clear();
3303 
3304  for (std::vector<unsigned int>::const_iterator it = inlierIndex.begin(); it != inlierIndex.end(); ++it) {
3305  m_matchRansacKeyPointsToPoints.push_back(std::pair<cv::KeyPoint, cv::Point3f>(
3306  m_queryFilteredKeyPoints[(size_t)(*it)], m_objectFilteredPoints[(size_t)(*it)]));
3307  mapOfInlierIndex[*it] = true;
3308  }
3309 
3310  for (size_t i = 0; i < m_queryFilteredKeyPoints.size(); i++) {
3311  if (mapOfInlierIndex.find((unsigned int)i) == mapOfInlierIndex.end()) {
3312  m_ransacOutliers.push_back(vpImagePoint(m_queryFilteredKeyPoints[i].pt.y, m_queryFilteredKeyPoints[i].pt.x));
3313  }
3314  }
3315 
3316  error = computePoseEstimationError(m_matchRansacKeyPointsToPoints, cam, cMo);
3317 
3318  m_ransacInliers.resize(m_matchRansacKeyPointsToPoints.size());
3319  std::transform(m_matchRansacKeyPointsToPoints.begin(), m_matchRansacKeyPointsToPoints.end(),
3320  m_ransacInliers.begin(), matchRansacToVpImage);
3321 
3322  elapsedTime += m_poseTime;
3323 
3324  return res;
3325  }
3326  else {
3327  std::vector<cv::Point2f> imageFilteredPoints;
3328  cv::KeyPoint::convert(m_queryFilteredKeyPoints, imageFilteredPoints);
3329  std::vector<int> inlierIndex;
3330  bool res = computePose(imageFilteredPoints, m_objectFilteredPoints, cam, cMo, inlierIndex, m_poseTime);
3331 
3332  std::map<int, bool> mapOfInlierIndex;
3333  m_matchRansacKeyPointsToPoints.clear();
3334 
3335  for (std::vector<int>::const_iterator it = inlierIndex.begin(); it != inlierIndex.end(); ++it) {
3336  m_matchRansacKeyPointsToPoints.push_back(std::pair<cv::KeyPoint, cv::Point3f>(
3337  m_queryFilteredKeyPoints[(size_t)(*it)], m_objectFilteredPoints[(size_t)(*it)]));
3338  mapOfInlierIndex[*it] = true;
3339  }
3340 
3341  for (size_t i = 0; i < m_queryFilteredKeyPoints.size(); i++) {
3342  if (mapOfInlierIndex.find((int)i) == mapOfInlierIndex.end()) {
3343  m_ransacOutliers.push_back(vpImagePoint(m_queryFilteredKeyPoints[i].pt.y, m_queryFilteredKeyPoints[i].pt.x));
3344  }
3345  }
3346 
3347  error = computePoseEstimationError(m_matchRansacKeyPointsToPoints, cam, cMo);
3348 
3349  m_ransacInliers.resize(m_matchRansacKeyPointsToPoints.size());
3350  std::transform(m_matchRansacKeyPointsToPoints.begin(), m_matchRansacKeyPointsToPoints.end(),
3351  m_ransacInliers.begin(), matchRansacToVpImage);
3352 
3353  elapsedTime += m_poseTime;
3354 
3355  return res;
3356  }
3357 }
3358 
3360  double &error, double &elapsedTime, bool (*func)(const vpHomogeneousMatrix &),
3361  const vpRect &rectangle)
3362 {
3363  vpImageConvert::convert(I_color, m_I);
3364  return (matchPoint(m_I, cam, cMo, error, elapsedTime, func, rectangle));
3365 }
3366 
3368  vpImagePoint &centerOfGravity, const bool isPlanarObject,
3369  std::vector<vpImagePoint> *imPts1, std::vector<vpImagePoint> *imPts2,
3370  double *meanDescriptorDistance, double *detectionScore, const vpRect &rectangle)
3371 {
3372  if (imPts1 != nullptr && imPts2 != nullptr) {
3373  imPts1->clear();
3374  imPts2->clear();
3375  }
3376 
3377  matchPoint(I, rectangle);
3378 
3379  double meanDescriptorDistanceTmp = 0.0;
3380  for (std::vector<cv::DMatch>::const_iterator it = m_filteredMatches.begin(); it != m_filteredMatches.end(); ++it) {
3381  meanDescriptorDistanceTmp += (double)it->distance;
3382  }
3383 
3384  meanDescriptorDistanceTmp /= (double)m_filteredMatches.size();
3385  double score = (double)m_filteredMatches.size() / meanDescriptorDistanceTmp;
3386 
3387  if (meanDescriptorDistance != nullptr) {
3388  *meanDescriptorDistance = meanDescriptorDistanceTmp;
3389  }
3390  if (detectionScore != nullptr) {
3391  *detectionScore = score;
3392  }
3393 
3394  if (m_filteredMatches.size() >= 4) {
3395  // Training / Reference 2D points
3396  std::vector<cv::Point2f> points1(m_filteredMatches.size());
3397  // Query / Current 2D points
3398  std::vector<cv::Point2f> points2(m_filteredMatches.size());
3399 
3400  for (size_t i = 0; i < m_filteredMatches.size(); i++) {
3401  points1[i] = cv::Point2f(m_trainKeyPoints[(size_t)m_filteredMatches[i].trainIdx].pt);
3402  points2[i] = cv::Point2f(m_queryFilteredKeyPoints[(size_t)m_filteredMatches[i].queryIdx].pt);
3403  }
3404 
3405  std::vector<vpImagePoint> inliers;
3406  if (isPlanarObject) {
3407 #if (VISP_HAVE_OPENCV_VERSION < 0x030000)
3408  cv::Mat homographyMatrix = cv::findHomography(points1, points2, CV_RANSAC);
3409 #else
3410  cv::Mat homographyMatrix = cv::findHomography(points1, points2, cv::RANSAC);
3411 #endif
3412 
3413  for (size_t i = 0; i < m_filteredMatches.size(); i++) {
3414  // Compute reprojection error
3415  cv::Mat realPoint = cv::Mat(3, 1, CV_64F);
3416  realPoint.at<double>(0, 0) = points1[i].x;
3417  realPoint.at<double>(1, 0) = points1[i].y;
3418  realPoint.at<double>(2, 0) = 1.f;
3419 
3420  cv::Mat reprojectedPoint = homographyMatrix * realPoint;
3421  double err_x = (reprojectedPoint.at<double>(0, 0) / reprojectedPoint.at<double>(2, 0)) - points2[i].x;
3422  double err_y = (reprojectedPoint.at<double>(1, 0) / reprojectedPoint.at<double>(2, 0)) - points2[i].y;
3423  double reprojectionError = std::sqrt(err_x * err_x + err_y * err_y);
3424 
3425  if (reprojectionError < 6.0) {
3426  inliers.push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x));
3427  if (imPts1 != nullptr) {
3428  imPts1->push_back(vpImagePoint((double)points1[i].y, (double)points1[i].x));
3429  }
3430 
3431  if (imPts2 != nullptr) {
3432  imPts2->push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x));
3433  }
3434  }
3435  }
3436  }
3437  else if (m_filteredMatches.size() >= 8) {
3438  cv::Mat fundamentalInliers;
3439  cv::Mat fundamentalMatrix = cv::findFundamentalMat(points1, points2, cv::FM_RANSAC, 3, 0.99, fundamentalInliers);
3440 
3441  for (size_t i = 0; i < (size_t)fundamentalInliers.rows; i++) {
3442  if (fundamentalInliers.at<uchar>((int)i, 0)) {
3443  inliers.push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x));
3444 
3445  if (imPts1 != nullptr) {
3446  imPts1->push_back(vpImagePoint((double)points1[i].y, (double)points1[i].x));
3447  }
3448 
3449  if (imPts2 != nullptr) {
3450  imPts2->push_back(vpImagePoint((double)points2[i].y, (double)points2[i].x));
3451  }
3452  }
3453  }
3454  }
3455 
3456  if (!inliers.empty()) {
3457  // Build a polygon with the list of inlier keypoints detected in the
3458  // current image to get the bounding box
3459  vpPolygon polygon(inliers);
3460  boundingBox = polygon.getBoundingBox();
3461 
3462  // Compute the center of gravity
3463  double meanU = 0.0, meanV = 0.0;
3464  for (std::vector<vpImagePoint>::const_iterator it = inliers.begin(); it != inliers.end(); ++it) {
3465  meanU += it->get_u();
3466  meanV += it->get_v();
3467  }
3468 
3469  meanU /= (double)inliers.size();
3470  meanV /= (double)inliers.size();
3471 
3472  centerOfGravity.set_u(meanU);
3473  centerOfGravity.set_v(meanV);
3474  }
3475  }
3476  else {
3477  // Too few matches
3478  return false;
3479  }
3480 
3481  if (m_detectionMethod == detectionThreshold) {
3482  return meanDescriptorDistanceTmp < m_detectionThreshold;
3483  }
3484  else {
3485  return score > m_detectionScore;
3486  }
3487 }
3488 
3490  vpHomogeneousMatrix &cMo, double &error, double &elapsedTime, vpRect &boundingBox,
3491  vpImagePoint &centerOfGravity, bool (*func)(const vpHomogeneousMatrix &),
3492  const vpRect &rectangle)
3493 {
3494  bool isMatchOk = matchPoint(I, cam, cMo, error, elapsedTime, func, rectangle);
3495  if (isMatchOk) {
3496  // Use the pose estimated to project the model points in the image
3497  vpPoint pt;
3498  vpImagePoint imPt;
3499  std::vector<vpImagePoint> modelImagePoints(m_trainVpPoints.size());
3500  size_t cpt = 0;
3501  for (std::vector<vpPoint>::const_iterator it = m_trainVpPoints.begin(); it != m_trainVpPoints.end(); ++it, cpt++) {
3502  pt = *it;
3503  pt.project(cMo);
3504  vpMeterPixelConversion::convertPoint(cam, pt.get_x(), pt.get_y(), imPt);
3505  modelImagePoints[cpt] = imPt;
3506  }
3507 
3508  // Build a polygon with the list of model image points to get the bounding
3509  // box
3510  vpPolygon polygon(modelImagePoints);
3511  boundingBox = polygon.getBoundingBox();
3512 
3513  // Compute the center of gravity of the current inlier keypoints
3514  double meanU = 0.0, meanV = 0.0;
3515  for (std::vector<vpImagePoint>::const_iterator it = m_ransacInliers.begin(); it != m_ransacInliers.end(); ++it) {
3516  meanU += it->get_u();
3517  meanV += it->get_v();
3518  }
3519 
3520  meanU /= (double)m_ransacInliers.size();
3521  meanV /= (double)m_ransacInliers.size();
3522 
3523  centerOfGravity.set_u(meanU);
3524  centerOfGravity.set_v(meanV);
3525  }
3526 
3527  return isMatchOk;
3528 }
3529 
3531  std::vector<std::vector<cv::KeyPoint> > &listOfKeypoints,
3532  std::vector<cv::Mat> &listOfDescriptors,
3533  std::vector<vpImage<unsigned char> > *listOfAffineI)
3534 {
3535 #if 0
3536  cv::Mat img;
3537  vpImageConvert::convert(I, img);
3538  listOfKeypoints.clear();
3539  listOfDescriptors.clear();
3540 
3541  for (int tl = 1; tl < 6; tl++) {
3542  double t = pow(2, 0.5 * tl);
3543  for (int phi = 0; phi < 180; phi += (int)(72.0 / t)) {
3544  std::vector<cv::KeyPoint> keypoints;
3545  cv::Mat descriptors;
3546 
3547  cv::Mat timg, mask, Ai;
3548  img.copyTo(timg);
3549 
3550  affineSkew(t, phi, timg, mask, Ai);
3551 
3552 
3553  if (listOfAffineI != nullptr) {
3554  cv::Mat img_disp;
3555  bitwise_and(mask, timg, img_disp);
3557  vpImageConvert::convert(img_disp, tI);
3558  listOfAffineI->push_back(tI);
3559  }
3560 #if 0
3561  cv::Mat img_disp;
3562  cv::bitwise_and(mask, timg, img_disp);
3563  cv::namedWindow("Skew", cv::WINDOW_AUTOSIZE); // Create a window for display.
3564  cv::imshow("Skew", img_disp);
3565  cv::waitKey(0);
3566 #endif
3567 
3568  for (std::map<std::string, cv::Ptr<cv::FeatureDetector> >::const_iterator it = m_detectors.begin();
3569  it != m_detectors.end(); ++it) {
3570  std::vector<cv::KeyPoint> kp;
3571  it->second->detect(timg, kp, mask);
3572  keypoints.insert(keypoints.end(), kp.begin(), kp.end());
3573  }
3574 
3575  double elapsedTime;
3576  extract(timg, keypoints, descriptors, elapsedTime);
3577 
3578  for (unsigned int i = 0; i < keypoints.size(); i++) {
3579  cv::Point3f kpt(keypoints[i].pt.x, keypoints[i].pt.y, 1.f);
3580  cv::Mat kpt_t = Ai * cv::Mat(kpt);
3581  keypoints[i].pt.x = kpt_t.at<float>(0, 0);
3582  keypoints[i].pt.y = kpt_t.at<float>(1, 0);
3583  }
3584 
3585  listOfKeypoints.push_back(keypoints);
3586  listOfDescriptors.push_back(descriptors);
3587  }
3588  }
3589 
3590 #else
3591  cv::Mat img;
3592  vpImageConvert::convert(I, img);
3593 
3594  // Create a vector for storing the affine skew parameters
3595  std::vector<std::pair<double, int> > listOfAffineParams;
3596  for (int tl = 1; tl < 6; tl++) {
3597  double t = pow(2, 0.5 * tl);
3598  for (int phi = 0; phi < 180; phi += (int)(72.0 / t)) {
3599  listOfAffineParams.push_back(std::pair<double, int>(t, phi));
3600  }
3601  }
3602 
3603  listOfKeypoints.resize(listOfAffineParams.size());
3604  listOfDescriptors.resize(listOfAffineParams.size());
3605 
3606  if (listOfAffineI != nullptr) {
3607  listOfAffineI->resize(listOfAffineParams.size());
3608  }
3609 
3610 #ifdef VISP_HAVE_OPENMP
3611 #pragma omp parallel for
3612 #endif
3613  for (int cpt = 0; cpt < static_cast<int>(listOfAffineParams.size()); cpt++) {
3614  std::vector<cv::KeyPoint> keypoints;
3615  cv::Mat descriptors;
3616 
3617  cv::Mat timg, mask, Ai;
3618  img.copyTo(timg);
3619 
3620  affineSkew(listOfAffineParams[(size_t)cpt].first, listOfAffineParams[(size_t)cpt].second, timg, mask, Ai);
3621 
3622  if (listOfAffineI != nullptr) {
3623  cv::Mat img_disp;
3624  bitwise_and(mask, timg, img_disp);
3626  vpImageConvert::convert(img_disp, tI);
3627  (*listOfAffineI)[(size_t)cpt] = tI;
3628  }
3629 
3630 #if 0
3631  cv::Mat img_disp;
3632  cv::bitwise_and(mask, timg, img_disp);
3633  cv::namedWindow("Skew", cv::WINDOW_AUTOSIZE); // Create a window for display.
3634  cv::imshow("Skew", img_disp);
3635  cv::waitKey(0);
3636 #endif
3637 
3638  for (std::map<std::string, cv::Ptr<cv::FeatureDetector> >::const_iterator it = m_detectors.begin();
3639  it != m_detectors.end(); ++it) {
3640  std::vector<cv::KeyPoint> kp;
3641  it->second->detect(timg, kp, mask);
3642  keypoints.insert(keypoints.end(), kp.begin(), kp.end());
3643  }
3644 
3645  double elapsedTime;
3646  extract(timg, keypoints, descriptors, elapsedTime);
3647 
3648  for (size_t i = 0; i < keypoints.size(); i++) {
3649  cv::Point3f kpt(keypoints[i].pt.x, keypoints[i].pt.y, 1.f);
3650  cv::Mat kpt_t = Ai * cv::Mat(kpt);
3651  keypoints[i].pt.x = kpt_t.at<float>(0, 0);
3652  keypoints[i].pt.y = kpt_t.at<float>(1, 0);
3653  }
3654 
3655  listOfKeypoints[(size_t)cpt] = keypoints;
3656  listOfDescriptors[(size_t)cpt] = descriptors;
3657  }
3658 #endif
3659 }
3660 
3662 {
3663  // vpBasicKeyPoint class
3665  m_currentImagePointsList.clear();
3666  m_matchedReferencePoints.clear();
3667  m_reference_computed = false;
3668 
3669  m_computeCovariance = false;
3670  m_covarianceMatrix = vpMatrix();
3671  m_currentImageId = 0;
3672  m_detectionMethod = detectionScore;
3673  m_detectionScore = 0.15;
3674  m_detectionThreshold = 100.0;
3675  m_detectionTime = 0.0;
3676  m_detectorNames.clear();
3677  m_detectors.clear();
3678  m_extractionTime = 0.0;
3679  m_extractorNames.clear();
3680  m_extractors.clear();
3681  m_filteredMatches.clear();
3682  m_filterType = ratioDistanceThreshold;
3683  m_imageFormat = jpgImageFormat;
3684  m_knnMatches.clear();
3685  m_mapOfImageId.clear();
3686  m_mapOfImages.clear();
3687  m_matcher = cv::Ptr<cv::DescriptorMatcher>();
3688  m_matcherName = "BruteForce-Hamming";
3689  m_matches.clear();
3690  m_matchingFactorThreshold = 2.0;
3691  m_matchingRatioThreshold = 0.85;
3692  m_matchingTime = 0.0;
3693  m_matchRansacKeyPointsToPoints.clear();
3694  m_nbRansacIterations = 200;
3695  m_nbRansacMinInlierCount = 100;
3696  m_objectFilteredPoints.clear();
3697  m_poseTime = 0.0;
3698  m_queryDescriptors = cv::Mat();
3699  m_queryFilteredKeyPoints.clear();
3700  m_queryKeyPoints.clear();
3701  m_ransacConsensusPercentage = 20.0;
3702  m_ransacFilterFlag = vpPose::NO_FILTER;
3703  m_ransacInliers.clear();
3704  m_ransacOutliers.clear();
3705  m_ransacParallel = true;
3706  m_ransacParallelNbThreads = 0;
3707  m_ransacReprojectionError = 6.0;
3708  m_ransacThreshold = 0.01;
3709  m_trainDescriptors = cv::Mat();
3710  m_trainKeyPoints.clear();
3711  m_trainPoints.clear();
3712  m_trainVpPoints.clear();
3713  m_useAffineDetection = false;
3714 #if (VISP_HAVE_OPENCV_VERSION >= 0x020400 && VISP_HAVE_OPENCV_VERSION < 0x030000)
3715  m_useBruteForceCrossCheck = true;
3716 #endif
3717  m_useConsensusPercentage = false;
3718  m_useKnn = true; // as m_filterType == ratioDistanceThreshold
3719  m_useMatchTrainToQuery = false;
3720  m_useRansacVVS = true;
3721  m_useSingleMatchFilter = true;
3722 
3723  m_detectorNames.push_back("ORB");
3724  m_extractorNames.push_back("ORB");
3725 
3726  init();
3727 }
3728 
3729 void vpKeyPoint::saveLearningData(const std::string &filename, bool binaryMode, bool saveTrainingImages)
3730 {
3731  std::string parent = vpIoTools::getParent(filename);
3732  if (!parent.empty()) {
3733  vpIoTools::makeDirectory(parent);
3734  }
3735 
3736  std::map<int, std::string> mapOfImgPath;
3737  if (saveTrainingImages) {
3738 #ifdef VISP_HAVE_MODULE_IO
3739  // Save the training image files in the same directory
3740  unsigned int cpt = 0;
3741 
3742  for (std::map<int, vpImage<unsigned char> >::const_iterator it = m_mapOfImages.begin(); it != m_mapOfImages.end();
3743  ++it, cpt++) {
3744  if (cpt > 999) {
3745  throw vpException(vpException::fatalError, "The number of training images to save is too big !");
3746  }
3747 
3748  std::stringstream ss;
3749  ss << "train_image_" << std::setfill('0') << std::setw(3) << cpt;
3750 
3751  switch (m_imageFormat) {
3752  case jpgImageFormat:
3753  ss << ".jpg";
3754  break;
3755 
3756  case pngImageFormat:
3757  ss << ".png";
3758  break;
3759 
3760  case ppmImageFormat:
3761  ss << ".ppm";
3762  break;
3763 
3764  case pgmImageFormat:
3765  ss << ".pgm";
3766  break;
3767 
3768  default:
3769  ss << ".png";
3770  break;
3771  }
3772 
3773  std::string imgFilename = ss.str();
3774  mapOfImgPath[it->first] = imgFilename;
3775  vpImageIo::write(it->second, parent + (!parent.empty() ? "/" : "") + imgFilename);
3776  }
3777 #else
3778  std::cout << "Warning: in vpKeyPoint::saveLearningData() training images "
3779  "are not saved because "
3780  "visp_io module is not available !"
3781  << std::endl;
3782 #endif
3783  }
3784 
3785  bool have3DInfo = m_trainPoints.size() > 0;
3786  if (have3DInfo && m_trainPoints.size() != m_trainKeyPoints.size()) {
3787  throw vpException(vpException::fatalError, "List of keypoints and list of 3D points have different size !");
3788  }
3789 
3790  if (binaryMode) {
3791  // Save the learning data into little endian binary file.
3792  std::ofstream file(filename.c_str(), std::ofstream::binary);
3793  if (!file.is_open()) {
3794  throw vpException(vpException::ioError, "Cannot create the file.");
3795  }
3796 
3797  // Write info about training images
3798  int nbImgs = (int)mapOfImgPath.size();
3799  vpIoTools::writeBinaryValueLE(file, nbImgs);
3800 
3801 #ifdef VISP_HAVE_MODULE_IO
3802  for (std::map<int, std::string>::const_iterator it = mapOfImgPath.begin(); it != mapOfImgPath.end(); ++it) {
3803  // Write image_id
3804  int id = it->first;
3806 
3807  // Write image path
3808  std::string path = it->second;
3809  int length = (int)path.length();
3810  vpIoTools::writeBinaryValueLE(file, length);
3811 
3812  for (int cpt = 0; cpt < length; cpt++) {
3813  file.write((char *)(&path[(size_t)cpt]), sizeof(path[(size_t)cpt]));
3814  }
3815  }
3816 #endif
3817 
3818  // Write if we have 3D point information
3819  int have3DInfoInt = have3DInfo ? 1 : 0;
3820  vpIoTools::writeBinaryValueLE(file, have3DInfoInt);
3821 
3822  int nRows = m_trainDescriptors.rows, nCols = m_trainDescriptors.cols;
3823  int descriptorType = m_trainDescriptors.type();
3824 
3825  // Write the number of descriptors
3826  vpIoTools::writeBinaryValueLE(file, nRows);
3827 
3828  // Write the size of the descriptor
3829  vpIoTools::writeBinaryValueLE(file, nCols);
3830 
3831  // Write the type of the descriptor
3832  vpIoTools::writeBinaryValueLE(file, descriptorType);
3833 
3834  for (int i = 0; i < nRows; i++) {
3835  unsigned int i_ = (unsigned int)i;
3836  // Write u
3837  float u = m_trainKeyPoints[i_].pt.x;
3839 
3840  // Write v
3841  float v = m_trainKeyPoints[i_].pt.y;
3843 
3844  // Write size
3845  float size = m_trainKeyPoints[i_].size;
3846  vpIoTools::writeBinaryValueLE(file, size);
3847 
3848  // Write angle
3849  float angle = m_trainKeyPoints[i_].angle;
3850  vpIoTools::writeBinaryValueLE(file, angle);
3851 
3852  // Write response
3853  float response = m_trainKeyPoints[i_].response;
3854  vpIoTools::writeBinaryValueLE(file, response);
3855 
3856  // Write octave
3857  int octave = m_trainKeyPoints[i_].octave;
3858  vpIoTools::writeBinaryValueLE(file, octave);
3859 
3860  // Write class_id
3861  int class_id = m_trainKeyPoints[i_].class_id;
3862  vpIoTools::writeBinaryValueLE(file, class_id);
3863 
3864  // Write image_id
3865 #ifdef VISP_HAVE_MODULE_IO
3866  std::map<int, int>::const_iterator it_findImgId = m_mapOfImageId.find(m_trainKeyPoints[i_].class_id);
3867  int image_id = (saveTrainingImages && it_findImgId != m_mapOfImageId.end()) ? it_findImgId->second : -1;
3868  vpIoTools::writeBinaryValueLE(file, image_id);
3869 #else
3870  int image_id = -1;
3871  // file.write((char *)(&image_id), sizeof(image_id));
3872  vpIoTools::writeBinaryValueLE(file, image_id);
3873 #endif
3874 
3875  if (have3DInfo) {
3876  float oX = m_trainPoints[i_].x, oY = m_trainPoints[i_].y, oZ = m_trainPoints[i_].z;
3877  // Write oX
3879 
3880  // Write oY
3882 
3883  // Write oZ
3885  }
3886 
3887  for (int j = 0; j < nCols; j++) {
3888  // Write the descriptor value
3889  switch (descriptorType) {
3890  case CV_8U:
3891  file.write((char *)(&m_trainDescriptors.at<unsigned char>(i, j)),
3892  sizeof(m_trainDescriptors.at<unsigned char>(i, j)));
3893  break;
3894 
3895  case CV_8S:
3896  file.write((char *)(&m_trainDescriptors.at<char>(i, j)), sizeof(m_trainDescriptors.at<char>(i, j)));
3897  break;
3898 
3899  case CV_16U:
3900  vpIoTools::writeBinaryValueLE(file, m_trainDescriptors.at<unsigned short int>(i, j));
3901  break;
3902 
3903  case CV_16S:
3904  vpIoTools::writeBinaryValueLE(file, m_trainDescriptors.at<short int>(i, j));
3905  break;
3906 
3907  case CV_32S:
3908  vpIoTools::writeBinaryValueLE(file, m_trainDescriptors.at<int>(i, j));
3909  break;
3910 
3911  case CV_32F:
3912  vpIoTools::writeBinaryValueLE(file, m_trainDescriptors.at<float>(i, j));
3913  break;
3914 
3915  case CV_64F:
3916  vpIoTools::writeBinaryValueLE(file, m_trainDescriptors.at<double>(i, j));
3917  break;
3918 
3919  default:
3920  throw vpException(vpException::fatalError, "Problem with the data type of descriptors !");
3921  break;
3922  }
3923  }
3924  }
3925 
3926  file.close();
3927  }
3928  else {
3929 #if defined(VISP_HAVE_PUGIXML)
3930  pugi::xml_document doc;
3931  pugi::xml_node node = doc.append_child(pugi::node_declaration);
3932  node.append_attribute("version") = "1.0";
3933  node.append_attribute("encoding") = "UTF-8";
3934 
3935  if (!doc) {
3936  throw vpException(vpException::ioError, "Error with file: ", filename.c_str());
3937  }
3938 
3939  pugi::xml_node root_node = doc.append_child("LearningData");
3940 
3941  // Write the training images info
3942  pugi::xml_node image_node = root_node.append_child("TrainingImageInfo");
3943 
3944 #ifdef VISP_HAVE_MODULE_IO
3945  for (std::map<int, std::string>::const_iterator it = mapOfImgPath.begin(); it != mapOfImgPath.end(); ++it) {
3946  pugi::xml_node image_info_node = image_node.append_child("trainImg");
3947  image_info_node.append_child(pugi::node_pcdata).set_value(it->second.c_str());
3948  std::stringstream ss;
3949  ss << it->first;
3950  image_info_node.append_attribute("image_id") = ss.str().c_str();
3951  }
3952 #endif
3953 
3954  // Write information about descriptors
3955  pugi::xml_node descriptors_info_node = root_node.append_child("DescriptorsInfo");
3956 
3957  int nRows = m_trainDescriptors.rows, nCols = m_trainDescriptors.cols;
3958  int descriptorType = m_trainDescriptors.type();
3959 
3960  // Write the number of rows
3961  descriptors_info_node.append_child("nrows").append_child(pugi::node_pcdata).text() = nRows;
3962 
3963  // Write the number of cols
3964  descriptors_info_node.append_child("ncols").append_child(pugi::node_pcdata).text() = nCols;
3965 
3966  // Write the descriptors type
3967  descriptors_info_node.append_child("type").append_child(pugi::node_pcdata).text() = descriptorType;
3968 
3969  for (int i = 0; i < nRows; i++) {
3970  unsigned int i_ = (unsigned int)i;
3971  pugi::xml_node descriptor_node = root_node.append_child("DescriptorInfo");
3972 
3973  descriptor_node.append_child("u").append_child(pugi::node_pcdata).text() = m_trainKeyPoints[i_].pt.x;
3974  descriptor_node.append_child("v").append_child(pugi::node_pcdata).text() = m_trainKeyPoints[i_].pt.y;
3975  descriptor_node.append_child("size").append_child(pugi::node_pcdata).text() = m_trainKeyPoints[i_].size;
3976  descriptor_node.append_child("angle").append_child(pugi::node_pcdata).text() = m_trainKeyPoints[i_].angle;
3977  descriptor_node.append_child("response").append_child(pugi::node_pcdata).text() = m_trainKeyPoints[i_].response;
3978  descriptor_node.append_child("octave").append_child(pugi::node_pcdata).text() = m_trainKeyPoints[i_].octave;
3979  descriptor_node.append_child("class_id").append_child(pugi::node_pcdata).text() = m_trainKeyPoints[i_].class_id;
3980 
3981 #ifdef VISP_HAVE_MODULE_IO
3982  std::map<int, int>::const_iterator it_findImgId = m_mapOfImageId.find(m_trainKeyPoints[i_].class_id);
3983  descriptor_node.append_child("image_id").append_child(pugi::node_pcdata).text() =
3984  ((saveTrainingImages && it_findImgId != m_mapOfImageId.end()) ? it_findImgId->second : -1);
3985 #else
3986  descriptor_node.append_child("image_id").append_child(pugi::node_pcdata).text() = -1;
3987 #endif
3988 
3989  if (have3DInfo) {
3990  descriptor_node.append_child("oX").append_child(pugi::node_pcdata).text() = m_trainPoints[i_].x;
3991  descriptor_node.append_child("oY").append_child(pugi::node_pcdata).text() = m_trainPoints[i_].y;
3992  descriptor_node.append_child("oZ").append_child(pugi::node_pcdata).text() = m_trainPoints[i_].z;
3993  }
3994 
3995  pugi::xml_node desc_node = descriptor_node.append_child("desc");
3996 
3997  for (int j = 0; j < nCols; j++) {
3998  switch (descriptorType) {
3999  case CV_8U: {
4000  // Promote an unsigned char to an int
4001  // val_tmp holds the numeric value that will be written
4002  // We save the value in numeric form otherwise xml library will not be
4003  // able to parse A better solution could be possible
4004  int val_tmp = m_trainDescriptors.at<unsigned char>(i, j);
4005  desc_node.append_child("val").append_child(pugi::node_pcdata).text() = val_tmp;
4006  } break;
4007 
4008  case CV_8S: {
4009  // Promote a char to an int
4010  // val_tmp holds the numeric value that will be written
4011  // We save the value in numeric form otherwise xml library will not be
4012  // able to parse A better solution could be possible
4013  int val_tmp = m_trainDescriptors.at<char>(i, j);
4014  desc_node.append_child("val").append_child(pugi::node_pcdata).text() = val_tmp;
4015  } break;
4016 
4017  case CV_16U:
4018  desc_node.append_child("val").append_child(pugi::node_pcdata).text() =
4019  m_trainDescriptors.at<unsigned short int>(i, j);
4020  break;
4021 
4022  case CV_16S:
4023  desc_node.append_child("val").append_child(pugi::node_pcdata).text() = m_trainDescriptors.at<short int>(i, j);
4024  break;
4025 
4026  case CV_32S:
4027  desc_node.append_child("val").append_child(pugi::node_pcdata).text() = m_trainDescriptors.at<int>(i, j);
4028  break;
4029 
4030  case CV_32F:
4031  desc_node.append_child("val").append_child(pugi::node_pcdata).text() = m_trainDescriptors.at<float>(i, j);
4032  break;
4033 
4034  case CV_64F:
4035  desc_node.append_child("val").append_child(pugi::node_pcdata).text() = m_trainDescriptors.at<double>(i, j);
4036  break;
4037 
4038  default:
4039  throw vpException(vpException::fatalError, "Problem with the data type of descriptors !");
4040  break;
4041  }
4042  }
4043  }
4044 
4045  doc.save_file(filename.c_str(), PUGIXML_TEXT(" "), pugi::format_default, pugi::encoding_utf8);
4046 #else
4047  throw vpException(vpException::ioError, "vpKeyPoint::saveLearningData() in xml needs built-in pugixml 3rdparty that is not available");
4048 #endif
4049  }
4050 }
4051 
4052 #if defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x030000)
4053 #ifndef DOXYGEN_SHOULD_SKIP_THIS
4054 // From OpenCV 2.4.11 source code.
4055 struct KeypointResponseGreaterThanThreshold
4056 {
4057  KeypointResponseGreaterThanThreshold(float _value) : value(_value) { }
4058  inline bool operator()(const cv::KeyPoint &kpt) const { return kpt.response >= value; }
4059  float value;
4060 };
4061 
4062 struct KeypointResponseGreater
4063 {
4064  inline bool operator()(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2) const { return kp1.response > kp2.response; }
4065 };
4066 
4067 // takes keypoints and culls them by the response
4068 void vpKeyPoint::KeyPointsFilter::retainBest(std::vector<cv::KeyPoint> &keypoints, int n_points)
4069 {
4070  // this is only necessary if the keypoints size is greater than the number
4071  // of desired points.
4072  if (n_points >= 0 && keypoints.size() > (size_t)n_points) {
4073  if (n_points == 0) {
4074  keypoints.clear();
4075  return;
4076  }
4077  // first use nth element to partition the keypoints into the best and
4078  // worst.
4079  std::nth_element(keypoints.begin(), keypoints.begin() + n_points, keypoints.end(), KeypointResponseGreater());
4080  // this is the boundary response, and in the case of FAST may be ambiguous
4081  float ambiguous_response = keypoints[(size_t)(n_points - 1)].response;
4082  // use std::partition to grab all of the keypoints with the boundary
4083  // response.
4084  std::vector<cv::KeyPoint>::const_iterator new_end = std::partition(
4085  keypoints.begin() + n_points, keypoints.end(), KeypointResponseGreaterThanThreshold(ambiguous_response));
4086  // resize the keypoints, given this new end point. nth_element and
4087  // partition reordered the points inplace
4088  keypoints.resize((size_t)(new_end - keypoints.begin()));
4089  }
4090 }
4091 
4092 struct RoiPredicate
4093 {
4094  RoiPredicate(const cv::Rect &_r) : r(_r) { }
4095 
4096  bool operator()(const cv::KeyPoint &keyPt) const { return !r.contains(keyPt.pt); }
4097 
4098  cv::Rect r;
4099 };
4100 
4101 void vpKeyPoint::KeyPointsFilter::runByImageBorder(std::vector<cv::KeyPoint> &keypoints, cv::Size imageSize,
4102  int borderSize)
4103 {
4104  if (borderSize > 0) {
4105  if (imageSize.height <= borderSize * 2 || imageSize.width <= borderSize * 2)
4106  keypoints.clear();
4107  else
4108  keypoints.erase(std::remove_if(keypoints.begin(), keypoints.end(),
4109  RoiPredicate(cv::Rect(
4110  cv::Point(borderSize, borderSize),
4111  cv::Point(imageSize.width - borderSize, imageSize.height - borderSize)))),
4112  keypoints.end());
4113  }
4114 }
4115 
4116 struct SizePredicate
4117 {
4118  SizePredicate(float _minSize, float _maxSize) : minSize(_minSize), maxSize(_maxSize) { }
4119 
4120  bool operator()(const cv::KeyPoint &keyPt) const
4121  {
4122  float size = keyPt.size;
4123  return (size < minSize) || (size > maxSize);
4124  }
4125 
4126  float minSize, maxSize;
4127 };
4128 
4129 void vpKeyPoint::KeyPointsFilter::runByKeypointSize(std::vector<cv::KeyPoint> &keypoints, float minSize, float maxSize)
4130 {
4131  CV_Assert(minSize >= 0);
4132  CV_Assert(maxSize >= 0);
4133  CV_Assert(minSize <= maxSize);
4134 
4135  keypoints.erase(std::remove_if(keypoints.begin(), keypoints.end(), SizePredicate(minSize, maxSize)), keypoints.end());
4136 }
4137 
4138 class MaskPredicate
4139 {
4140 public:
4141  MaskPredicate(const cv::Mat &_mask) : mask(_mask) { }
4142  bool operator()(const cv::KeyPoint &key_pt) const
4143  {
4144  return mask.at<uchar>((int)(key_pt.pt.y + 0.5f), (int)(key_pt.pt.x + 0.5f)) == 0;
4145  }
4146 
4147 private:
4148  const cv::Mat mask;
4149 };
4150 
4151 void vpKeyPoint::KeyPointsFilter::runByPixelsMask(std::vector<cv::KeyPoint> &keypoints, const cv::Mat &mask)
4152 {
4153  if (mask.empty())
4154  return;
4155 
4156  keypoints.erase(std::remove_if(keypoints.begin(), keypoints.end(), MaskPredicate(mask)), keypoints.end());
4157 }
4158 
4159 struct KeyPoint_LessThan
4160 {
4161  KeyPoint_LessThan(const std::vector<cv::KeyPoint> &_kp) : kp(&_kp) { }
4162  bool operator()(/*int i, int j*/ size_t i, size_t j) const
4163  {
4164  const cv::KeyPoint &kp1 = (*kp)[/*(size_t)*/ i];
4165  const cv::KeyPoint &kp2 = (*kp)[/*(size_t)*/ j];
4166  if (!vpMath::equal(kp1.pt.x, kp2.pt.x,
4167  std::numeric_limits<float>::epsilon())) { // if (kp1.pt.x !=
4168  // kp2.pt.x) {
4169  return kp1.pt.x < kp2.pt.x;
4170  }
4171 
4172  if (!vpMath::equal(kp1.pt.y, kp2.pt.y,
4173  std::numeric_limits<float>::epsilon())) { // if (kp1.pt.y !=
4174  // kp2.pt.y) {
4175  return kp1.pt.y < kp2.pt.y;
4176  }
4177 
4178  if (!vpMath::equal(kp1.size, kp2.size,
4179  std::numeric_limits<float>::epsilon())) { // if (kp1.size !=
4180  // kp2.size) {
4181  return kp1.size > kp2.size;
4182  }
4183 
4184  if (!vpMath::equal(kp1.angle, kp2.angle,
4185  std::numeric_limits<float>::epsilon())) { // if (kp1.angle !=
4186  // kp2.angle) {
4187  return kp1.angle < kp2.angle;
4188  }
4189 
4190  if (!vpMath::equal(kp1.response, kp2.response,
4191  std::numeric_limits<float>::epsilon())) { // if (kp1.response !=
4192  // kp2.response) {
4193  return kp1.response > kp2.response;
4194  }
4195 
4196  if (kp1.octave != kp2.octave) {
4197  return kp1.octave > kp2.octave;
4198  }
4199 
4200  if (kp1.class_id != kp2.class_id) {
4201  return kp1.class_id > kp2.class_id;
4202  }
4203 
4204  return i < j;
4205  }
4206  const std::vector<cv::KeyPoint> *kp;
4207 };
4208 
4209 void vpKeyPoint::KeyPointsFilter::removeDuplicated(std::vector<cv::KeyPoint> &keypoints)
4210 {
4211  size_t i, j, n = keypoints.size();
4212  std::vector<size_t> kpidx(n);
4213  std::vector<uchar> mask(n, (uchar)1);
4214 
4215  for (i = 0; i < n; i++) {
4216  kpidx[i] = i;
4217  }
4218  std::sort(kpidx.begin(), kpidx.end(), KeyPoint_LessThan(keypoints));
4219  for (i = 1, j = 0; i < n; i++) {
4220  cv::KeyPoint &kp1 = keypoints[kpidx[i]];
4221  cv::KeyPoint &kp2 = keypoints[kpidx[j]];
4222  // if (kp1.pt.x != kp2.pt.x || kp1.pt.y != kp2.pt.y || kp1.size !=
4223  // kp2.size || kp1.angle != kp2.angle) {
4224  if (!vpMath::equal(kp1.pt.x, kp2.pt.x, std::numeric_limits<float>::epsilon()) ||
4225  !vpMath::equal(kp1.pt.y, kp2.pt.y, std::numeric_limits<float>::epsilon()) ||
4226  !vpMath::equal(kp1.size, kp2.size, std::numeric_limits<float>::epsilon()) ||
4227  !vpMath::equal(kp1.angle, kp2.angle, std::numeric_limits<float>::epsilon())) {
4228  j = i;
4229  }
4230  else {
4231  mask[kpidx[i]] = 0;
4232  }
4233  }
4234 
4235  for (i = j = 0; i < n; i++) {
4236  if (mask[i]) {
4237  if (i != j) {
4238  keypoints[j] = keypoints[i];
4239  }
4240  j++;
4241  }
4242  }
4243  keypoints.resize(j);
4244 }
4245 
4246 /*
4247  * PyramidAdaptedFeatureDetector
4248  */
4249 vpKeyPoint::PyramidAdaptedFeatureDetector::PyramidAdaptedFeatureDetector(const cv::Ptr<cv::FeatureDetector> &detector,
4250  int maxLevel)
4251  : m_detector(detector), m_maxLevel(maxLevel)
4252 { }
4253 
4254 bool vpKeyPoint::PyramidAdaptedFeatureDetector::empty() const
4255 {
4256  return m_detector.empty() || (cv::FeatureDetector *)m_detector->empty();
4257 }
4258 
4259 void vpKeyPoint::PyramidAdaptedFeatureDetector::detect(cv::InputArray image,
4260  CV_OUT std::vector<cv::KeyPoint> &keypoints, cv::InputArray mask)
4261 {
4262  detectImpl(image.getMat(), keypoints, mask.getMat());
4263 }
4264 
4265 void vpKeyPoint::PyramidAdaptedFeatureDetector::detectImpl(const cv::Mat &image, std::vector<cv::KeyPoint> &keypoints,
4266  const cv::Mat &mask) const
4267 {
4268  cv::Mat src = image;
4269  cv::Mat src_mask = mask;
4270 
4271  cv::Mat dilated_mask;
4272  if (!mask.empty()) {
4273  cv::dilate(mask, dilated_mask, cv::Mat());
4274  cv::Mat mask255(mask.size(), CV_8UC1, cv::Scalar(0));
4275  mask255.setTo(cv::Scalar(255), dilated_mask != 0);
4276  dilated_mask = mask255;
4277  }
4278 
4279  for (int l = 0, multiplier = 1; l <= m_maxLevel; ++l, multiplier *= 2) {
4280  // Detect on current level of the pyramid
4281  std::vector<cv::KeyPoint> new_pts;
4282  m_detector->detect(src, new_pts, src_mask);
4283  std::vector<cv::KeyPoint>::iterator it = new_pts.begin(), end = new_pts.end();
4284  for (; it != end; ++it) {
4285  it->pt.x *= multiplier;
4286  it->pt.y *= multiplier;
4287  it->size *= multiplier;
4288  it->octave = l;
4289  }
4290  keypoints.insert(keypoints.end(), new_pts.begin(), new_pts.end());
4291 
4292  // Downsample
4293  if (l < m_maxLevel) {
4294  cv::Mat dst;
4295  pyrDown(src, dst);
4296  src = dst;
4297 
4298  if (!mask.empty())
4299 #if (VISP_HAVE_OPENCV_VERSION >= 0x050000)
4300  resize(dilated_mask, src_mask, src.size(), 0, 0, cv::INTER_AREA);
4301 #else
4302  resize(dilated_mask, src_mask, src.size(), 0, 0, CV_INTER_AREA);
4303 #endif
4304  }
4305  }
4306 
4307  if (!mask.empty())
4308  vpKeyPoint::KeyPointsFilter::runByPixelsMask(keypoints, mask);
4309 }
4310 #endif
4311 #endif
4312 
4313 END_VISP_NAMESPACE
4314 
4315 #elif !defined(VISP_BUILD_SHARED_LIBS)
4316 // Work around to avoid warning: libvisp_vision.a(vpKeyPoint.cpp.o) has no symbols
4317 void dummy_vpKeyPoint() { };
4318 #endif
std::vector< unsigned int > m_matchedReferencePoints
std::vector< vpImagePoint > m_currentImagePointsList
std::vector< vpImagePoint > m_referenceImagePointsList
Generic class defining intrinsic camera parameters.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
Class to define RGB colors available for display functionalities.
Definition: vpColor.h:157
static const vpColor red
Definition: vpColor.h:198
static const vpColor none
Definition: vpColor.h:210
static const vpColor green
Definition: vpColor.h:201
static void convertFromOpenCV(const cv::KeyPoint &from, vpImagePoint &to)
Definition: vpConvert.cpp:228
static void displayCircle(const vpImage< unsigned char > &I, const vpImageCircle &circle, const vpColor &color, bool fill=false, unsigned int thickness=1)
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ ioError
I/O error.
Definition: vpException.h:67
@ fatalError
Fatal error.
Definition: vpException.h:72
const char * what() const
Definition: vpException.cpp:71
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix inverse() const
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
static void read(vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition: vpImageIo.cpp:147
static void write(const vpImage< unsigned char > &I, const std::string &filename, int backend=IO_DEFAULT_BACKEND)
Definition: vpImageIo.cpp:291
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
double get_j() const
Definition: vpImagePoint.h:125
void set_ij(double ii, double jj)
Definition: vpImagePoint.h:320
void set_u(double u)
Definition: vpImagePoint.h:335
void set_v(double v)
Definition: vpImagePoint.h:346
double get_i() const
Definition: vpImagePoint.h:114
unsigned int getWidth() const
Definition: vpImage.h:242
void insert(const vpImage< Type > &src, const vpImagePoint &topLeft)
Definition: vpImage.h:639
unsigned int getHeight() const
Definition: vpImage.h:181
static bool isAbsolutePathname(const std::string &pathname)
Definition: vpIoTools.cpp:1468
static void readBinaryValueLE(std::ifstream &file, int16_t &short_value)
static void makeDirectory(const std::string &dirname)
Definition: vpIoTools.cpp:550
static void writeBinaryValueLE(std::ofstream &file, const int16_t short_value)
static std::string getParent(const std::string &pathname)
Definition: vpIoTools.cpp:1314
unsigned int matchPoint(const vpImage< unsigned char > &I)
@ detectionThreshold
Definition: vpKeyPoint.h:287
@ detectionScore
Definition: vpKeyPoint.h:289
void getTrainKeyPoints(std::vector< cv::KeyPoint > &keyPoints) const
static void compute3DForPointsOnCylinders(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< cv::KeyPoint > &candidates, const std::vector< vpCylinder > &cylinders, const std::vector< std::vector< std::vector< vpImagePoint > > > &vectorOfCylinderRois, std::vector< cv::Point3f > &points, cv::Mat *descriptors=nullptr)
Definition: vpKeyPoint.cpp:572
void detectExtractAffine(const vpImage< unsigned char > &I, std::vector< std::vector< cv::KeyPoint > > &listOfKeypoints, std::vector< cv::Mat > &listOfDescriptors, std::vector< vpImage< unsigned char > > *listOfAffineI=nullptr)
void initMatcher(const std::string &matcherName)
vpKeyPoint(const vpFeatureDetectorType &detectorType, const vpFeatureDescriptorType &descriptorType, const std::string &matcherName, const vpFilterMatchingType &filterType=ratioDistanceThreshold)
Definition: vpKeyPoint.cpp:87
void display(const vpImage< unsigned char > &IRef, const vpImage< unsigned char > &ICurrent, unsigned int size=3)
void match(const cv::Mat &trainDescriptors, const cv::Mat &queryDescriptors, std::vector< cv::DMatch > &matches, double &elapsedTime)
static void compute3D(const cv::KeyPoint &candidate, const std::vector< vpPoint > &roi, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, cv::Point3f &point)
Definition: vpKeyPoint.cpp:427
vpFeatureDetectorType
Definition: vpKeyPoint.h:305
@ DETECTOR_KAZE
KAZE detector.
Definition: vpKeyPoint.h:337
@ DETECTOR_BRISK
BRISK detector.
Definition: vpKeyPoint.h:328
@ DETECTOR_AKAZE
AKAZE detector.
Definition: vpKeyPoint.h:336
@ DETECTOR_MSER
MSER detector.
Definition: vpKeyPoint.h:331
@ DETECTOR_AGAST
AGAST detector.
Definition: vpKeyPoint.h:335
@ DETECTOR_FAST
FAST detector.
Definition: vpKeyPoint.h:329
@ DETECTOR_GFTT
GFTT detector.
Definition: vpKeyPoint.h:330
@ DETECTOR_ORB
ORB detector.
Definition: vpKeyPoint.h:332
@ DETECTOR_SimpleBlob
SimpleBlob detector.
Definition: vpKeyPoint.h:333
void reset()
void createImageMatching(vpImage< unsigned char > &IRef, vpImage< unsigned char > &ICurrent, vpImage< unsigned char > &IMatching)
Definition: vpKeyPoint.cpp:875
void loadLearningData(const std::string &filename, bool binaryMode=false, bool append=false)
bool computePose(const std::vector< cv::Point2f > &imagePoints, const std::vector< cv::Point3f > &objectPoints, const vpCameraParameters &cam, vpHomogeneousMatrix &cMo, std::vector< int > &inlierIndex, double &elapsedTime, bool(*func)(const vpHomogeneousMatrix &)=nullptr)
Definition: vpKeyPoint.cpp:690
void extract(const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &keyPoints, cv::Mat &descriptors, std::vector< cv::Point3f > *trainPoints=nullptr)
void detect(const vpImage< unsigned char > &I, std::vector< cv::KeyPoint > &keyPoints, const vpRect &rectangle=vpRect())
Definition: vpKeyPoint.cpp:989
static void compute3DForPointsInPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, std::vector< cv::KeyPoint > &candidates, const std::vector< vpPolygon > &polygons, const std::vector< std::vector< vpPoint > > &roisPt, std::vector< cv::Point3f > &points, cv::Mat *descriptors=nullptr)
Definition: vpKeyPoint.cpp:481
bool matchPointAndDetect(const vpImage< unsigned char > &I, vpRect &boundingBox, vpImagePoint &centerOfGravity, const bool isPlanarObject=true, std::vector< vpImagePoint > *imPts1=nullptr, std::vector< vpImagePoint > *imPts2=nullptr, double *meanDescriptorDistance=nullptr, double *detectionScore=nullptr, const vpRect &rectangle=vpRect())
vpFeatureDescriptorType
Definition: vpKeyPoint.h:359
@ DESCRIPTOR_LATCH
LATCH descriptor.
Definition: vpKeyPoint.h:392
@ DESCRIPTOR_AKAZE
AKAZE descriptor.
Definition: vpKeyPoint.h:384
@ DESCRIPTOR_BRIEF
BRIEF descriptor.
Definition: vpKeyPoint.h:389
@ DESCRIPTOR_FREAK
FREAK descriptor.
Definition: vpKeyPoint.h:391
@ DESCRIPTOR_ORB
ORB descriptor.
Definition: vpKeyPoint.h:382
@ DESCRIPTOR_KAZE
KAZE descriptor.
Definition: vpKeyPoint.h:385
@ DESCRIPTOR_DAISY
DAISY descriptor.
Definition: vpKeyPoint.h:390
@ DESCRIPTOR_BRISK
BRISK descriptor.
Definition: vpKeyPoint.h:381
void getQueryKeyPoints(std::vector< cv::KeyPoint > &keyPoints, bool matches=true) const
void saveLearningData(const std::string &filename, bool binaryMode=false, bool saveTrainingImages=true)
@ ppmImageFormat
Definition: vpKeyPoint.h:299
@ jpgImageFormat
Definition: vpKeyPoint.h:297
@ pngImageFormat
Definition: vpKeyPoint.h:298
@ pgmImageFormat
Definition: vpKeyPoint.h:300
vpFilterMatchingType
Definition: vpKeyPoint.h:271
@ stdAndRatioDistanceThreshold
Definition: vpKeyPoint.h:279
@ constantFactorDistanceThreshold
Definition: vpKeyPoint.h:272
@ ratioDistanceThreshold
Definition: vpKeyPoint.h:276
@ stdDistanceThreshold
Definition: vpKeyPoint.h:274
@ noFilterMatching
Definition: vpKeyPoint.h:281
void displayMatching(const vpImage< unsigned char > &IRef, vpImage< unsigned char > &IMatching, unsigned int crossSize, unsigned int lineThickness=1, const vpColor &color=vpColor::green)
unsigned int buildReference(const vpImage< unsigned char > &I)
Definition: vpKeyPoint.cpp:211
void loadConfigFile(const std::string &configFile)
void getTrainPoints(std::vector< cv::Point3f > &points) const
void getObjectPoints(std::vector< cv::Point3f > &objectPoints) const
void insertImageMatching(const vpImage< unsigned char > &IRef, const vpImage< unsigned char > &ICurrent, vpImage< unsigned char > &IMatching)
static bool isNaN(double value)
Definition: vpMath.cpp:92
static bool equal(double x, double y, double threshold=0.001)
Definition: vpMath.h:459
static int round(double x)
Definition: vpMath.h:410
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
This class defines the container for a plane geometrical structure.
Definition: vpPlane.h:56
double getD() const
Definition: vpPlane.h:106
double getA() const
Definition: vpPlane.h:100
double getC() const
Definition: vpPlane.h:104
double getB() const
Definition: vpPlane.h:102
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
double get_oX() const
Get the point oX coordinate in the object frame.
Definition: vpPoint.cpp:415
void set_x(double x)
Set the point x coordinate in the image plane.
Definition: vpPoint.cpp:468
double get_y() const
Get the point y coordinate in the image plane.
Definition: vpPoint.cpp:426
double get_oZ() const
Get the point oZ coordinate in the object frame.
Definition: vpPoint.cpp:419
void set_oY(double oY)
Set the point oY coordinate in the object frame.
Definition: vpPoint.cpp:461
double get_x() const
Get the point x coordinate in the image plane.
Definition: vpPoint.cpp:424
void set_oZ(double oZ)
Set the point oZ coordinate in the object frame.
Definition: vpPoint.cpp:463
void set_oX(double oX)
Set the point oX coordinate in the object frame.
Definition: vpPoint.cpp:459
double get_oY() const
Get the point oY coordinate in the object frame.
Definition: vpPoint.cpp:417
void setWorldCoordinates(double oX, double oY, double oZ)
Definition: vpPoint.cpp:113
void set_y(double y)
Set the point y coordinate in the image plane.
Definition: vpPoint.cpp:470
Defines a generic 2D polygon.
Definition: vpPolygon.h:103
vpRect getBoundingBox() const
Definition: vpPolygon.h:164
bool isInside(const vpImagePoint &iP, const PointInPolygonMethod &method=PnPolyRayCasting) const
Definition: vpPolygon.cpp:402
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition: vpPose.h:77
void setRansacMaxTrials(const int &rM)
Definition: vpPose.h:406
void addPoint(const vpPoint &P)
Definition: vpPose.cpp:96
void setRansacNbInliersToReachConsensus(const unsigned int &nbC)
Definition: vpPose.h:387
vpMatrix getCovarianceMatrix() const
Definition: vpPose.h:440
@ RANSAC
Definition: vpPose.h:87
void setCovarianceComputation(const bool &flag)
Definition: vpPose.h:429
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, FuncCheckValidityPose func=nullptr)
Definition: vpPose.cpp:385
std::vector< unsigned int > getRansacInlierIndex() const
Definition: vpPose.h:416
void setRansacFilterFlag(const RANSAC_FILTER_FLAGS &flag)
Definition: vpPose.h:459
@ NO_FILTER
No filter is applied.
Definition: vpPose.h:108
void setUseParallelRansac(bool use)
Definition: vpPose.h:490
std::vector< vpPoint > getRansacInliers() const
Definition: vpPose.h:421
void setNbParallelRansacThreads(int nb)
Definition: vpPose.h:476
void setRansacThreshold(const double &t)
Definition: vpPose.h:392
Defines a rectangle in the plane.
Definition: vpRect.h:79
double getWidth() const
Definition: vpRect.h:227
double getLeft() const
Definition: vpRect.h:173
double getRight() const
Definition: vpRect.h:179
double getBottom() const
Definition: vpRect.h:97
double getHeight() const
Definition: vpRect.h:166
double getTop() const
Definition: vpRect.h:192
Implementation of a rotation vector as axis-angle minimal representation.
Class that consider the case of a translation vector.
void parse(const std::string &filename)
vpMatchingMethodEnum getMatchingMethod() const
VISP_EXPORT double measureTimeMs()