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