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