Settings.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "find_object/Camera.h"
29 #include "find_object/Settings.h"
31 
32 #include <QtCore/QSettings>
33 #include <QtCore/QStringList>
34 #include <QtCore/QDir>
35 #include <stdio.h>
36 #include <opencv2/calib3d/calib3d.hpp>
37 #include <opencv2/opencv_modules.hpp>
38 
39 #if CV_MAJOR_VERSION < 3
40 #include <opencv2/gpu/gpu.hpp>
41 #define CVCUDA cv::gpu
42 #else
43 #include <opencv2/core/cuda.hpp>
44 #define CVCUDA cv::cuda
45 #ifdef HAVE_OPENCV_CUDAFEATURES2D
46 #include <opencv2/cudafeatures2d.hpp>
47 #endif
48 #endif
49 
50 #ifdef HAVE_OPENCV_NONFREE
51  #if CV_MAJOR_VERSION == 2 && CV_MINOR_VERSION >=4
52  #include <opencv2/nonfree/gpu.hpp>
53  #include <opencv2/nonfree/features2d.hpp>
54  #endif
55 #endif
56 #ifdef HAVE_OPENCV_XFEATURES2D
57  #include <opencv2/xfeatures2d.hpp>
58  #include <opencv2/xfeatures2d/cuda.hpp>
59 #endif
60 
61 #if FINDOBJECT_TORCH == 1
63 #endif
64 
65 namespace find_object {
66 
71 Settings Settings::dummyInit_;
72 QString Settings::iniPath_;
73 
75 {
76 #ifdef WIN32
77  return QString("%1/Documents/%2").arg(QDir::homePath()).arg(PROJECT_NAME);
78 #else
79  return QString("%1").arg(QDir::homePath());
80 #endif
81 }
82 
84 {
85 #ifdef WIN32
86  return QString("%1/Documents/%2/%3").arg(QDir::homePath()).arg(PROJECT_NAME).arg(Settings::iniDefaultFileName());
87 #else
88  return QString("%1/.%2/%3").arg(QDir::homePath()).arg(PROJECT_PREFIX).arg(Settings::iniDefaultFileName());
89 #endif
90 }
91 
93 {
94  if(!iniPath_.isNull())
95  {
96  return iniPath_;
97  }
98  return iniDefaultPath();
99 }
100 
101 ParametersMap Settings::init(const QString & fileName)
102 {
103  iniPath_ = fileName;
104  return loadSettings(iniPath_);
105 }
106 
107 ParametersMap Settings::loadSettings(const QString & fileName)
108 {
109  ParametersMap loadedParameters;
110  QString path = fileName;
111  if(fileName.isEmpty())
112  {
113  path = iniPath();
114  }
115  if(!path.isEmpty())
116  {
117  QSettings ini(path, QSettings::IniFormat);
118  for(ParametersMap::const_iterator iter = defaultParameters_.begin(); iter!=defaultParameters_.end(); ++iter)
119  {
120  const QString & key = iter.key();
121  QVariant value = ini.value(key, QVariant());
122  if(value.isValid())
123  {
124  QString str = value.toString();
125  if(str.contains(";"))
126  {
127  if(str.size() != getParameter(key).toString().size())
128  {
129  // If a string list is modified, update the value
130  // Assuming format ##:VA;VB;VC
131  int index = str.split(':').first().toInt();
132  str = getParameter(key).toString();
133  str = QString::number(index)+":"+ str.split(':').back();
134  value = QVariant(str);
135  UINFO("Updated list of parameter \"%s\"", key.toStdString().c_str());
136  }
137  int index = str.split(':').first().toInt();
138  if(key.compare(Settings::kFeature2D_1Detector()) == 0)
139  {
140 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
141 #if FINDOBJECT_NONFREE == 0
142  if(index == 5 || index == 7)
143  {
144  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
145  UWARN("Trying to set \"%s\" to SIFT/SURF but Find-Object isn't built "
146  "with the nonfree module from OpenCV. Keeping default combo value: %s.",
147  Settings::kFeature2D_1Detector().toStdString().c_str(),
148  Settings::defaultFeature2D_1Detector().split(':').last().split(";").at(index).toStdString().c_str());
149  }
150 #endif
151 #elif FINDOBJECT_NONFREE == 0
152  if(index == 7)
153  {
154  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
155  UWARN("Trying to set \"%s\" to SURF but Find-Object isn't built "
156  "with the nonfree module from OpenCV. Keeping default combo value: %s.",
157  Settings::kFeature2D_1Detector().toStdString().c_str(),
158  Settings::defaultFeature2D_1Detector().split(':').last().split(";").at(index).toStdString().c_str());
159  }
160 #endif
161 #if FINDOBJECT_TORCH == 0
162  if(index == 12)
163  {
164  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
165  UWARN("Trying to set \"%s\" to SuperPointTorch but Find-Object isn't built "
166  "with the Torch. Keeping default combo value: %s.",
167  Settings::kFeature2D_1Detector().toStdString().c_str(),
168  Settings::defaultFeature2D_1Detector().split(':').last().split(";").at(index).toStdString().c_str());
169  }
170 #endif
171  }
172  else if(key.compare(Settings::kFeature2D_2Descriptor()) == 0)
173  {
174 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
175 #if FINDOBJECT_NONFREE == 0
176  if(index == 2 || index == 3)
177  {
178  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
179  UWARN("Trying to set \"%s\" to SIFT/SURF but Find-Object isn't built "
180  "with the nonfree module from OpenCV. Keeping default combo value: %s.",
181  Settings::kFeature2D_2Descriptor().toStdString().c_str(),
182  Settings::defaultFeature2D_2Descriptor().split(':').last().split(";").at(index).toStdString().c_str());
183  }
184 #endif
185 #elif FINDOBJECT_NONFREE == 0
186  if(index == 3)
187  {
188  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
189  UWARN("Trying to set \"%s\" to SURF but Find-Object isn't built "
190  "with the nonfree module from OpenCV. Keeping default combo value: %s.",
191  Settings::kFeature2D_2Descriptor().toStdString().c_str(),
192  Settings::defaultFeature2D_2Descriptor().split(':').last().split(";").at(index).toStdString().c_str());
193  }
194 #endif
195 #if FINDOBJECT_TORCH == 0
196  if(index == 11)
197  {
198  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
199  UWARN("Trying to set \"%s\" to SuperPointTorch but Find-Object isn't built "
200  "with the Torch. Keeping default combo value: %s.",
201  Settings::kFeature2D_1Detector().toStdString().c_str(),
202  Settings::defaultFeature2D_1Detector().split(':').last().split(";").at(index).toStdString().c_str());
203  }
204 #endif
205  }
206  str = getParameter(key).toString();
207  str = QString::number(index)+":"+ str.split(':').back();
208  value = QVariant(str);
209  }
210  loadedParameters.insert(key, value);
211  setParameter(key, value);
212  }
213  }
214 
215  //validate descriptors and nearest neighbor compatibilities
216  bool isBinaryDescriptor = currentDescriptorType().compare("ORB") == 0 ||
217  currentDescriptorType().compare("Brief") == 0 ||
218  currentDescriptorType().compare("BRISK") == 0 ||
219  currentDescriptorType().compare("FREAK") == 0 ||
220  currentDescriptorType().compare("AKAZE") == 0 ||
221  currentDescriptorType().compare("LATCH") == 0 ||
222  currentDescriptorType().compare("LUCID") == 0;
223  bool binToFloat = getNearestNeighbor_7ConvertBinToFloat();
224  if(isBinaryDescriptor && !binToFloat && currentNearestNeighborType().compare("Lsh") != 0 && currentNearestNeighborType().compare("BruteForce") != 0)
225  {
226  UWARN("Current selected descriptor type (\"%s\") is binary while nearest neighbor strategy is not (\"%s\").\n"
227  "Falling back to \"BruteForce\" nearest neighbor strategy with Hamming distance (by default).",
228  currentDescriptorType().toStdString().c_str(),
229  currentNearestNeighborType().toStdString().c_str());
230  QString tmp = Settings::getNearestNeighbor_1Strategy();
231  *tmp.begin() = '6'; // set BruteForce
232  setNearestNeighbor_1Strategy(tmp);
233  loadedParameters.insert(Settings::kNearestNeighbor_1Strategy(), tmp);
234  tmp = Settings::getNearestNeighbor_2Distance_type();
235  *tmp.begin() = '8'; // set HAMMING
236  setNearestNeighbor_2Distance_type(tmp);
237  loadedParameters.insert(Settings::kNearestNeighbor_2Distance_type(), tmp);
238  }
239 
240  UINFO("Settings loaded from %s.", path.toStdString().c_str());
241  }
242  else
243  {
245  UINFO("Settings set to defaults.");
246  }
247 
248  if(CVCUDA::getCudaEnabledDeviceCount() == 0)
249  {
250 #if FINDOBJECT_NONFREE == 1
251  Settings::setFeature2D_SURF_gpu(false);
252 #endif
253  Settings::setFeature2D_Fast_gpu(false);
254  Settings::setFeature2D_ORB_gpu(false);
255  Settings::setNearestNeighbor_BruteForce_gpu(false);
256  }
257  return loadedParameters;
258 }
259 
260 void Settings::loadWindowSettings(QByteArray & windowGeometry, QByteArray & windowState, const QString & fileName)
261 {
262  QString path = fileName;
263  if(fileName.isEmpty())
264  {
265  path = iniPath();
266  }
267 
268  if(!path.isEmpty())
269  {
270  QSettings ini(path, QSettings::IniFormat);
271 
272  QVariant value = ini.value("windowGeometry", QVariant());
273  if(value.isValid())
274  {
275  windowGeometry = value.toByteArray();
276  }
277 
278  value = ini.value("windowState", QVariant());
279  if(value.isValid())
280  {
281  windowState = value.toByteArray();
282  }
283 
284  UINFO("Window settings loaded from %s", path.toStdString().c_str());
285  }
286 }
287 
288 void Settings::saveSettings(const QString & fileName)
289 {
290  QString path = fileName;
291  if(fileName.isEmpty())
292  {
293  path = iniPath();
294  }
295  if(!path.isEmpty())
296  {
297  QSettings ini(path, QSettings::IniFormat);
298  for(ParametersMap::const_iterator iter = parameters_.begin(); iter!=parameters_.end(); ++iter)
299  {
300  QString type = Settings::getParametersType().value(iter.key());
301  if(type.compare("float") == 0)
302  {
303  ini.setValue(iter.key(), QString::number(iter.value().toFloat(),'g',6));
304  }
305  else
306  {
307  ini.setValue(iter.key(), iter.value());
308  }
309  }
310  UINFO("Settings saved to %s", path.toStdString().c_str());
311  }
312 }
313 
314 void Settings::saveWindowSettings(const QByteArray & windowGeometry, const QByteArray & windowState, const QString & fileName)
315 {
316  QString path = fileName;
317  if(fileName.isEmpty())
318  {
319  path = iniPath();
320  }
321  if(!path.isEmpty())
322  {
323  QSettings ini(path, QSettings::IniFormat);
324  if(!windowGeometry.isEmpty())
325  {
326  ini.setValue("windowGeometry", windowGeometry);
327  }
328  if(!windowState.isEmpty())
329  {
330  ini.setValue("windowState", windowState);
331  }
332  UINFO("Window settings saved to %s", path.toStdString().c_str());
333  }
334 }
335 
336 #if FINDOBJECT_NONFREE == 1
337 class GPUSURF : public Feature2D
338 {
339 public:
340  GPUSURF(double hessianThreshold,
341  int nOctaves,
342  int nOctaveLayers,
343  bool extended,
344  float keypointsRatio,
345  bool upright) :
346  surf_(hessianThreshold,
347  nOctaves,
348  nOctaveLayers,
349  extended,
350  keypointsRatio,
351  upright)
352  {
353  }
354  virtual ~GPUSURF() {}
355 
356  virtual void detect(const cv::Mat & image,
357  std::vector<cv::KeyPoint> & keypoints,
358  const cv::Mat & mask = cv::Mat())
359  {
360  CVCUDA::GpuMat imgGpu(image);
361  CVCUDA::GpuMat maskGpu(mask);
362  try
363  {
364  surf_(imgGpu, maskGpu, keypoints);
365  }
366  catch(cv::Exception &e)
367  {
368  UERROR("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF "
369  "is too high for the size of the image (%d,%d).)",
370  e.msg.c_str(),
371  surf_.nOctaves,
372  image.cols,
373  image.rows);
374  }
375  }
376 
377  virtual void compute( const cv::Mat& image,
378  std::vector<cv::KeyPoint>& keypoints,
379  cv::Mat& descriptors)
380  {
381  std::vector<float> d;
382  CVCUDA::GpuMat imgGpu(image);
383  CVCUDA::GpuMat descriptorsGPU;
384  try
385  {
386  surf_(imgGpu, CVCUDA::GpuMat(), keypoints, descriptorsGPU, true);
387  }
388  catch(cv::Exception &e)
389  {
390  UERROR("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF "
391  "is too high for the size of the image (%d,%d).)",
392  e.msg.c_str(),
393  surf_.nOctaves,
394  image.cols,
395  image.rows);
396  }
397 
398  // Download descriptors
399  if (descriptorsGPU.empty())
400  descriptors = cv::Mat();
401  else
402  {
403  UASSERT(descriptorsGPU.type() == CV_32F);
404  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
405  descriptorsGPU.download(descriptors);
406  }
407  }
408 
409  virtual void detectAndCompute( const cv::Mat& image,
410  std::vector<cv::KeyPoint>& keypoints,
411  cv::Mat& descriptors,
412  const cv::Mat & mask = cv::Mat())
413  {
414  std::vector<float> d;
415  CVCUDA::GpuMat imgGpu(image);
416  CVCUDA::GpuMat descriptorsGPU;
417  CVCUDA::GpuMat maskGpu(mask);
418  try
419  {
420  surf_(imgGpu, maskGpu, keypoints, descriptorsGPU, false);
421  }
422  catch(cv::Exception &e)
423  {
424  UERROR("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF "
425  "is too high for the size of the image (%d,%d).)",
426  e.msg.c_str(),
427  surf_.nOctaves,
428  image.cols,
429  image.rows);
430  }
431 
432  // Download descriptors
433  if (descriptorsGPU.empty())
434  descriptors = cv::Mat();
435  else
436  {
437  UASSERT(descriptorsGPU.type() == CV_32F);
438  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
439  descriptorsGPU.download(descriptors);
440  }
441  }
442 
443 private:
444 #if CV_MAJOR_VERSION < 3
445  CVCUDA::SURF_GPU surf_;
446 #else
447  CVCUDA::SURF_CUDA surf_;
448 #endif
449 };
450 #endif
451 
452 class GPUFAST : public Feature2D
453 {
454 public:
455  GPUFAST(int threshold=Settings::defaultFeature2D_Fast_threshold(),
456  bool nonmaxSuppression=Settings::defaultFeature2D_Fast_nonmaxSuppression(),
457 #if CV_MAJOR_VERSION < 3
458  double keypointsRatio=Settings::defaultFeature2D_Fast_keypointsRatio())
459  : fast_(threshold,
460  nonmaxSuppression,
461  keypointsRatio)
462 #else
463  int max_npoints=Settings::defaultFeature2D_Fast_maxNpoints())
464 #ifdef HAVE_OPENCV_CUDAFEATURES2D
465  : fast_(CVCUDA::FastFeatureDetector::create(
466  threshold,
467  nonmaxSuppression,
468  cv::FastFeatureDetector::TYPE_9_16,
469  max_npoints))
470 #endif
471 #endif
472  {
473  }
474  virtual ~GPUFAST() {}
475 
476  virtual void detect(const cv::Mat & image,
477  std::vector<cv::KeyPoint> & keypoints,
478  const cv::Mat & mask = cv::Mat())
479  {
480  CVCUDA::GpuMat imgGpu(image);
481  CVCUDA::GpuMat maskGpu(mask);
482 #if CV_MAJOR_VERSION < 3
483  fast_(imgGpu, maskGpu, keypoints);
484 #else
485 #ifdef HAVE_OPENCV_CUDAFEATURES2D
486  CVCUDA::GpuMat keypointsGpu;
487  fast_->detectAsync(imgGpu, keypointsGpu, maskGpu);
488  fast_->convert(keypointsGpu, keypoints);
489 #endif
490 #endif
491  }
492  virtual void compute( const cv::Mat& image,
493  std::vector<cv::KeyPoint>& keypoints,
494  cv::Mat& descriptors)
495  {
496  UERROR("GPUFAST:computeDescriptors() Should not be used!");
497  }
498  virtual void detectAndCompute( const cv::Mat& image,
499  std::vector<cv::KeyPoint>& keypoints,
500  cv::Mat& descriptors,
501  const cv::Mat & mask = cv::Mat())
502  {
503  UERROR("GPUFAST:detectAndCompute() Should not be used!");
504  }
505 
506 private:
507 #if CV_MAJOR_VERSION < 3
508  CVCUDA::FAST_GPU fast_;
509 #else
510 #ifdef HAVE_OPENCV_CUDAFEATURES2D
511  cv::Ptr<CVCUDA::FastFeatureDetector> fast_;
512 #endif
513 #endif
514 };
515 
516 class GPUORB : public Feature2D
517 {
518 public:
519  GPUORB(int nFeatures = Settings::defaultFeature2D_ORB_nFeatures(),
520  float scaleFactor = Settings::defaultFeature2D_ORB_scaleFactor(),
521  int nLevels = Settings::defaultFeature2D_ORB_nLevels(),
522  int edgeThreshold = Settings::defaultFeature2D_ORB_edgeThreshold(),
523  int firstLevel = Settings::defaultFeature2D_ORB_firstLevel(),
524  int WTA_K = Settings::defaultFeature2D_ORB_WTA_K(),
525  int scoreType = Settings::defaultFeature2D_ORB_scoreType(),
526  int patchSize = Settings::defaultFeature2D_ORB_patchSize(),
527  int fastThreshold = Settings::defaultFeature2D_Fast_threshold(),
528 #if CV_MAJOR_VERSION < 3
529  bool fastNonmaxSupression = Settings::defaultFeature2D_Fast_nonmaxSuppression())
530  : orb_(nFeatures,
531  scaleFactor,
532  nLevels,
533  edgeThreshold ,
534  firstLevel,
535  WTA_K,
536  scoreType,
537  patchSize)
538 #else
539  bool blurForDescriptor = Settings::defaultFeature2D_ORB_blurForDescriptor())
540 #ifdef HAVE_OPENCV_CUDAFEATURES2D
541  : orb_(CVCUDA::ORB::create(nFeatures,
542  scaleFactor,
543  nLevels,
544  edgeThreshold ,
545  firstLevel,
546  WTA_K,
547  scoreType,
548  patchSize,
549  fastThreshold,
550  blurForDescriptor))
551 #endif
552 #endif
553  {
554 #if CV_MAJOR_VERSION < 3
555  orb_.setFastParams(fastThreshold, fastNonmaxSupression);
556 #endif
557  }
558  virtual ~GPUORB() {}
559 
560  virtual void detect(const cv::Mat & image,
561  std::vector<cv::KeyPoint> & keypoints,
562  const cv::Mat & mask = cv::Mat())
563  {
564 
565  CVCUDA::GpuMat imgGpu(image);
566  CVCUDA::GpuMat maskGpu(mask);
567 
568  try
569  {
570 #if CV_MAJOR_VERSION < 3
571  orb_(imgGpu, maskGpu, keypoints);
572 #else
573 #ifdef HAVE_OPENCV_CUDAFEATURES2D
574  CVCUDA::GpuMat keypointsGpu;
575  orb_->detectAsync(imgGpu, keypointsGpu, maskGpu);
576  orb_->convert(keypointsGpu, keypoints);
577 #endif
578 #endif
579  }
580  catch(cv::Exception &e)
581  {
582  UERROR("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
583  e.msg.c_str(),
584  image.cols,
585  image.rows);
586  }
587  }
588 
589  virtual void compute( const cv::Mat& image,
590  std::vector<cv::KeyPoint>& keypoints,
591  cv::Mat& descriptors)
592  {
593  std::vector<float> d;
594 
595  CVCUDA::GpuMat imgGpu(image);
596  CVCUDA::GpuMat descriptorsGPU;
597 
598  try
599  {
600 #if CV_MAJOR_VERSION < 3
601  orb_(imgGpu, CVCUDA::GpuMat(), keypoints, descriptorsGPU); // No option to use provided keypoints!?
602 #else
603 #ifdef HAVE_OPENCV_CUDAFEATURES2D
604  UERROR("OpenCV 3 ORB-GPU doesn't support extracting ORB descriptors from already extracted keypoints. "
605  "Use ORB as feature detector too or desactivate ORB-GPU.");
606  //orb_->computeAsync(imgGpu, keypoints, descriptorsGPU, true);
607 #endif
608 #endif
609  }
610  catch(cv::Exception &e)
611  {
612  UERROR("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
613  e.msg.c_str(),
614  image.cols,
615  image.rows);
616  }
617  // Download descriptors
618  if (descriptorsGPU.empty())
619  descriptors = cv::Mat();
620  else
621  {
622  UASSERT(descriptorsGPU.type() == CV_8U);
623  descriptors = cv::Mat(descriptorsGPU.size(), CV_8U);
624  descriptorsGPU.download(descriptors);
625  }
626  }
627 
628  virtual void detectAndCompute( const cv::Mat& image,
629  std::vector<cv::KeyPoint>& keypoints,
630  cv::Mat& descriptors,
631  const cv::Mat & mask = cv::Mat())
632  {
633  std::vector<float> d;
634 
635  CVCUDA::GpuMat imgGpu(image);
636  CVCUDA::GpuMat descriptorsGPU;
637  CVCUDA::GpuMat maskGpu(mask);
638 
639  try
640  {
641 #if CV_MAJOR_VERSION < 3
642  orb_(imgGpu, CVCUDA::GpuMat(), keypoints, descriptorsGPU); // No option to use provided keypoints!?
643 #else
644 #ifdef HAVE_OPENCV_CUDAFEATURES2D
645  CVCUDA::GpuMat keypointsGpu;
646  orb_->detectAndComputeAsync(imgGpu, maskGpu, keypointsGpu, descriptorsGPU, false);
647  orb_->convert(keypointsGpu, keypoints);
648 #endif
649 #endif
650  }
651  catch(cv::Exception &e)
652  {
653  UERROR("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
654  e.msg.c_str(),
655  image.cols,
656  image.rows);
657  }
658  // Download descriptors
659  if (descriptorsGPU.empty())
660  descriptors = cv::Mat();
661  else
662  {
663  UASSERT(descriptorsGPU.type() == CV_8U);
664  descriptors = cv::Mat(descriptorsGPU.size(), CV_8U);
665  descriptorsGPU.download(descriptors);
666  }
667  }
668 
669 private:
670 #if CV_MAJOR_VERSION < 3
671  CVCUDA::ORB_GPU orb_;
672 #else
673 #ifdef HAVE_OPENCV_CUDAFEATURES2D
674  cv::Ptr<CVCUDA::ORB> orb_;
675 #endif
676 #endif
677 };
678 
679 #if FINDOBJECT_TORCH == 1
680 class SuperPointTorch : public Feature2D
681 {
682 public:
683  SuperPointTorch(
684  const QString & modelPath,
685  float threshold = Settings::defaultFeature2D_SuperPointTorch_threshold(),
686  bool nms = Settings::defaultFeature2D_SuperPointTorch_NMS(),
687  int nmsRadius = Settings::defaultFeature2D_SuperPointTorch_NMS_radius(),
688  bool cuda = Settings::defaultFeature2D_SuperPointTorch_cuda())
689  {
690  superPoint_ = cv::Ptr<SPDetector>(new SPDetector(modelPath.toStdString(), threshold, nms, nmsRadius, cuda));
691  }
692 
693  virtual ~SuperPointTorch() {}
694 
695  virtual void detect(const cv::Mat & image,
696  std::vector<cv::KeyPoint> & keypoints,
697  const cv::Mat & mask = cv::Mat())
698  {
699  keypoints = superPoint_->detect(image);
700  }
701 
702  virtual void compute( const cv::Mat& image,
703  std::vector<cv::KeyPoint>& keypoints,
704  cv::Mat& descriptors)
705  {
706  descriptors = superPoint_->compute(keypoints);
707  }
708 
709  virtual void detectAndCompute( const cv::Mat& image,
710  std::vector<cv::KeyPoint>& keypoints,
711  cv::Mat& descriptors,
712  const cv::Mat & mask = cv::Mat())
713  {
714  keypoints = superPoint_->detect(image);
715  descriptors = superPoint_->compute(keypoints);
716  }
717 private:
718  cv::Ptr<SPDetector> superPoint_;
719 };
720 #endif
721 
723 {
724  Feature2D * feature2D = 0;
725  QString str = getFeature2D_1Detector();
726  UDEBUG("Type=%s", str.toStdString().c_str());
727  QStringList split = str.split(':');
728  if(split.size()==2)
729  {
730  bool ok = false;
731  int index = split.first().toInt(&ok);
732  if(ok)
733  {
734  QStringList strategies = split.last().split(';');
735 
736  if(index>=0 && index<strategies.size())
737  {
738 
739  //check for nonfree stuff
740 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
741 #if FINDOBJECT_NONFREE == 0
742  if(strategies.at(index).compare("SIFT") == 0 ||
743  strategies.at(index).compare("SURF") == 0)
744  {
745  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
746  UERROR("Find-Object is not built with OpenCV nonfree module so "
747  "SIFT/SURF cannot be used! Using default \"%s\" instead.",
748  strategies.at(index).toStdString().c_str());
749 
750  }
751 #endif
752 #elif FINDOBJECT_NONFREE == 0
753  if(strategies.at(index).compare("SURF") == 0)
754  {
755  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
756  UERROR("Find-Object is not built with OpenCV nonfree module so "
757  "SURF cannot be used! Using default \"%s\" instead.",
758  strategies.at(index).toStdString().c_str());
759 
760  }
761 #endif
762 
763 #if FINDOBJECT_TORCH == 0
764  //check for nonfree stuff
765  if(strategies.at(index).compare("SuperPointTorch") == 0)
766  {
767  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
768  UERROR("Find-Object is not built with Torch so "
769  "SuperPointTorch cannot be used! Using default \"%s\" instead.",
770  strategies.at(index).toStdString().c_str());
771 
772  }
773 #endif
774 
775 #if CV_MAJOR_VERSION < 3
776  if(strategies.at(index).compare("AGAST") == 0 ||
777  strategies.at(index).compare("KAZE") == 0 ||
778  strategies.at(index).compare("AKAZE") == 0)
779  {
780  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
781  UERROR("Find-Object is built with OpenCV 2 so "
782  "AGAST/KAZE/AKAZE cannot be used! Using default \"%s\" instead.",
783  strategies.at(index).toStdString().c_str());
784 
785  }
786 #else
787  if(strategies.at(index).compare("Dense") == 0)
788  {
789  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
790  UERROR("Find-Object is built with OpenCV 3 so "
791  "Dense cannot be used! Using default \"%s\" instead.",
792  strategies.at(index).toStdString().c_str());
793 
794  }
795 #ifndef HAVE_OPENCV_XFEATURES2D
796  if(strategies.at(index).compare("Star") == 0)
797  {
798  index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
799  UERROR("Find-Object is not built with OpenCV xfeatures2d module so "
800  "Star cannot be used! Using default \"%s\" instead.",
801  strategies.at(index).toStdString().c_str());
802 
803  }
804 #endif
805 #endif
806 
807  if(strategies.at(index).compare("Dense") == 0)
808  {
809 #if CV_MAJOR_VERSION < 3
810  feature2D = new Feature2D(cv::Ptr<cv::FeatureDetector>(new cv::DenseFeatureDetector(
811  getFeature2D_Dense_initFeatureScale(),
812  getFeature2D_Dense_featureScaleLevels(),
813  getFeature2D_Dense_featureScaleMul(),
814  getFeature2D_Dense_initXyStep(),
815  getFeature2D_Dense_initImgBound(),
816  getFeature2D_Dense_varyXyStepWithScale(),
817  getFeature2D_Dense_varyImgBoundWithScale())));
818 #else
819  UWARN("Find-Object is not built with OpenCV 2 so Dense cannot be used!");
820 #endif
821  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
822  }
823  else if(strategies.at(index).compare("Fast") == 0)
824  {
825  if(getFeature2D_Fast_gpu() && CVCUDA::getCudaEnabledDeviceCount())
826  {
827  feature2D = new GPUFAST(
828  getFeature2D_Fast_threshold(),
829  getFeature2D_Fast_nonmaxSuppression());
830  UDEBUG("type=%s GPU", strategies.at(index).toStdString().c_str());
831  }
832  else
833  {
834 #if CV_MAJOR_VERSION < 3
835  feature2D = new Feature2D(cv::Ptr<cv::FeatureDetector>(new cv::FastFeatureDetector(
836  getFeature2D_Fast_threshold(),
837  getFeature2D_Fast_nonmaxSuppression())));
838 #else
839  feature2D = new Feature2D(cv::FastFeatureDetector::create(
840  getFeature2D_Fast_threshold(),
841  getFeature2D_Fast_nonmaxSuppression()));
842 #endif
843  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
844  }
845  }
846  else if(strategies.at(index).compare("AGAST") == 0)
847  {
848 #if CV_MAJOR_VERSION < 3
849  UWARN("Find-Object is not built with OpenCV 3 so AGAST cannot be used!");
850 #else
851  feature2D = new Feature2D(cv::AgastFeatureDetector::create(
852  getFeature2D_AGAST_threshold(),
853  getFeature2D_AGAST_nonmaxSuppression()));
854 #endif
855  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
856  }
857  else if(strategies.at(index).compare("GFTT") == 0)
858  {
859 #if CV_MAJOR_VERSION < 3
860  feature2D = new Feature2D(cv::Ptr<cv::FeatureDetector>(new cv::GFTTDetector(
861  getFeature2D_GFTT_maxCorners(),
862  getFeature2D_GFTT_qualityLevel(),
863  getFeature2D_GFTT_minDistance(),
864  getFeature2D_GFTT_blockSize(),
865  getFeature2D_GFTT_useHarrisDetector(),
866  getFeature2D_GFTT_k())));
867 #else
868  feature2D = new Feature2D(cv::GFTTDetector::create(
869  getFeature2D_GFTT_maxCorners(),
870  getFeature2D_GFTT_qualityLevel(),
871  getFeature2D_GFTT_minDistance(),
872  getFeature2D_GFTT_blockSize(),
873  getFeature2D_GFTT_useHarrisDetector(),
874  getFeature2D_GFTT_k()));
875 #endif
876  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
877  }
878  else if(strategies.at(index).compare("MSER") == 0)
879  {
880 #if CV_MAJOR_VERSION < 3
881  feature2D = new Feature2D(cv::Ptr<cv::FeatureDetector>(new cv::MSER(
882  getFeature2D_MSER_delta(),
883  getFeature2D_MSER_minArea(),
884  getFeature2D_MSER_maxArea(),
885  getFeature2D_MSER_maxVariation(),
886  getFeature2D_MSER_minDiversity(),
887  getFeature2D_MSER_maxEvolution(),
888  getFeature2D_MSER_areaThreshold(),
889  getFeature2D_MSER_minMargin(),
890  getFeature2D_MSER_edgeBlurSize())));
891 #else
892  feature2D = new Feature2D(cv::MSER::create(
893  getFeature2D_MSER_delta(),
894  getFeature2D_MSER_minArea(),
895  getFeature2D_MSER_maxArea(),
896  getFeature2D_MSER_maxVariation(),
897  getFeature2D_MSER_minDiversity(),
898  getFeature2D_MSER_maxEvolution(),
899  getFeature2D_MSER_areaThreshold(),
900  getFeature2D_MSER_minMargin(),
901  getFeature2D_MSER_edgeBlurSize()));
902 #endif
903  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
904  }
905  else if(strategies.at(index).compare("ORB") == 0)
906  {
907  if(getFeature2D_ORB_gpu() && CVCUDA::getCudaEnabledDeviceCount())
908  {
909  feature2D = new GPUORB(
910  getFeature2D_ORB_nFeatures(),
911  getFeature2D_ORB_scaleFactor(),
912  getFeature2D_ORB_nLevels(),
913  getFeature2D_ORB_edgeThreshold(),
914  getFeature2D_ORB_firstLevel(),
915  getFeature2D_ORB_WTA_K(),
916  getFeature2D_ORB_scoreType(),
917  getFeature2D_ORB_patchSize(),
918  getFeature2D_Fast_threshold(),
919 #if CV_MAJOR_VERSION < 3
920  getFeature2D_Fast_nonmaxSuppression());
921 #else
922  getFeature2D_ORB_blurForDescriptor());
923 #endif
924  UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
925  }
926  else
927  {
928 #if CV_MAJOR_VERSION < 3
929  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::ORB(
930  getFeature2D_ORB_nFeatures(),
931  getFeature2D_ORB_scaleFactor(),
932  getFeature2D_ORB_nLevels(),
933  getFeature2D_ORB_edgeThreshold(),
934  getFeature2D_ORB_firstLevel(),
935  getFeature2D_ORB_WTA_K(),
936  getFeature2D_ORB_scoreType(),
937  getFeature2D_ORB_patchSize())));
938 #else
939  feature2D = new Feature2D(cv::ORB::create(
940  getFeature2D_ORB_nFeatures(),
941  getFeature2D_ORB_scaleFactor(),
942  getFeature2D_ORB_nLevels(),
943  getFeature2D_ORB_edgeThreshold(),
944  getFeature2D_ORB_firstLevel(),
945  getFeature2D_ORB_WTA_K(),
946 #if CV_MAJOR_VERSION > 3
947  (cv::ORB::ScoreType)getFeature2D_ORB_scoreType(),
948 #else
949  getFeature2D_ORB_scoreType(),
950 #endif
951  getFeature2D_ORB_patchSize(),
952  getFeature2D_Fast_threshold()));
953 #endif
954  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
955  }
956  }
957  else if(strategies.at(index).compare("Star") == 0)
958  {
959 #if CV_MAJOR_VERSION < 3
960  feature2D = new Feature2D(cv::Ptr<cv::FeatureDetector>(new cv::StarFeatureDetector(
961  getFeature2D_Star_maxSize(),
962  getFeature2D_Star_responseThreshold(),
963  getFeature2D_Star_lineThresholdProjected(),
964  getFeature2D_Star_lineThresholdBinarized(),
965  getFeature2D_Star_suppressNonmaxSize())));
966 #else
967 #ifdef HAVE_OPENCV_XFEATURES2D
968  feature2D = new Feature2D(cv::xfeatures2d::StarDetector::create(
969  getFeature2D_Star_maxSize(),
970  getFeature2D_Star_responseThreshold(),
971  getFeature2D_Star_lineThresholdProjected(),
972  getFeature2D_Star_lineThresholdBinarized(),
973  getFeature2D_Star_suppressNonmaxSize()));
974 #else
975  UWARN("Find-Object is not built with OpenCV xfeatures2d module so Star cannot be used!");
976 #endif
977 #endif
978  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
979  }
980  else if(strategies.at(index).compare("BRISK") == 0)
981  {
982 #if CV_MAJOR_VERSION < 3
983  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::BRISK(
984  getFeature2D_BRISK_thresh(),
985  getFeature2D_BRISK_octaves(),
986  getFeature2D_BRISK_patternScale())));
987 #else
988  feature2D = new Feature2D(cv::BRISK::create(
989  getFeature2D_BRISK_thresh(),
990  getFeature2D_BRISK_octaves(),
991  getFeature2D_BRISK_patternScale()));
992 #endif
993  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
994  }
995  else if(strategies.at(index).compare("KAZE") == 0)
996  {
997 #if CV_MAJOR_VERSION < 3
998  UWARN("Find-Object is not built with OpenCV 3 so KAZE cannot be used!");
999 #else
1000  feature2D = new Feature2D(cv::KAZE::create(
1001  getFeature2D_KAZE_extended(),
1002  getFeature2D_KAZE_upright(),
1003  getFeature2D_KAZE_threshold(),
1004  getFeature2D_KAZE_nOctaves(),
1005  getFeature2D_KAZE_nOctaveLayers(),
1006  cv::KAZE::DIFF_PM_G2)); // FIXME: make a parameter
1007 #endif
1008  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1009  }
1010  else if(strategies.at(index).compare("AKAZE") == 0)
1011  {
1012 #if CV_MAJOR_VERSION < 3
1013  UWARN("Find-Object is not built with OpenCV 3 so AKAZE cannot be used!");
1014 #else
1015  feature2D = new Feature2D(cv::AKAZE::create(
1016  cv::AKAZE::DESCRIPTOR_MLDB, // FIXME: make a parameter
1017  getFeature2D_AKAZE_descriptorSize(),
1018  getFeature2D_AKAZE_descriptorChannels(),
1019  getFeature2D_AKAZE_threshold(),
1020  getFeature2D_AKAZE_nOctaves(),
1021  getFeature2D_AKAZE_nOctaveLayers(),
1022  cv::KAZE::DIFF_PM_G2)); // FIXME: make a parameter
1023 #endif
1024  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1025  }
1026 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
1027 #if FINDOBJECT_NONFREE == 1
1028  else if(strategies.at(index).compare("SIFT") == 0)
1029  {
1030 #if CV_MAJOR_VERSION < 3
1031  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::SIFT(
1032  getFeature2D_SIFT_nfeatures(),
1033  getFeature2D_SIFT_nOctaveLayers(),
1034  getFeature2D_SIFT_contrastThreshold(),
1035  getFeature2D_SIFT_edgeThreshold(),
1036  getFeature2D_SIFT_sigma())));
1037 #else
1038  feature2D = new Feature2D(cv::xfeatures2d::SIFT::create(
1039  getFeature2D_SIFT_nfeatures(),
1040  getFeature2D_SIFT_nOctaveLayers(),
1041  getFeature2D_SIFT_contrastThreshold(),
1042  getFeature2D_SIFT_edgeThreshold(),
1043  getFeature2D_SIFT_sigma()));
1044 #endif
1045  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1046  }
1047  else if(strategies.at(index).compare("SURF") == 0)
1048  {
1049  if(getFeature2D_SURF_gpu() && CVCUDA::getCudaEnabledDeviceCount())
1050  {
1051  feature2D = new GPUSURF(
1052  getFeature2D_SURF_hessianThreshold(),
1053  getFeature2D_SURF_nOctaves(),
1054  getFeature2D_SURF_nOctaveLayers(),
1055  getFeature2D_SURF_extended(),
1056  getFeature2D_SURF_keypointsRatio(),
1057  getFeature2D_SURF_upright());
1058  UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
1059  }
1060  else
1061  {
1062 #if CV_MAJOR_VERSION < 3
1063  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::SURF(
1064  getFeature2D_SURF_hessianThreshold(),
1065  getFeature2D_SURF_nOctaves(),
1066  getFeature2D_SURF_nOctaveLayers(),
1067  getFeature2D_SURF_extended(),
1068  getFeature2D_SURF_upright())));
1069 #else
1070  feature2D = new Feature2D(cv::xfeatures2d::SURF::create(
1071  getFeature2D_SURF_hessianThreshold(),
1072  getFeature2D_SURF_nOctaves(),
1073  getFeature2D_SURF_nOctaveLayers(),
1074  getFeature2D_SURF_extended(),
1075  getFeature2D_SURF_upright()));
1076 #endif
1077  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1078  }
1079  }
1080 #endif
1081 #else // >= 4.3.0-dev
1082  else if(strategies.at(index).compare("SIFT") == 0)
1083  {
1084  feature2D = new Feature2D(cv::SIFT::create(
1085  getFeature2D_SIFT_nfeatures(),
1086  getFeature2D_SIFT_nOctaveLayers(),
1087  getFeature2D_SIFT_contrastThreshold(),
1088  getFeature2D_SIFT_edgeThreshold(),
1089  getFeature2D_SIFT_sigma()));
1090  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1091  }
1092 #if FINDOBJECT_NONFREE == 1
1093  else if(strategies.at(index).compare("SURF") == 0)
1094  {
1095  if(getFeature2D_SURF_gpu() && CVCUDA::getCudaEnabledDeviceCount())
1096  {
1097  feature2D = new GPUSURF(
1098  getFeature2D_SURF_hessianThreshold(),
1099  getFeature2D_SURF_nOctaves(),
1100  getFeature2D_SURF_nOctaveLayers(),
1101  getFeature2D_SURF_extended(),
1102  getFeature2D_SURF_keypointsRatio(),
1103  getFeature2D_SURF_upright());
1104  UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
1105  }
1106  else
1107  {
1108  feature2D = new Feature2D(cv::xfeatures2d::SURF::create(
1109  getFeature2D_SURF_hessianThreshold(),
1110  getFeature2D_SURF_nOctaves(),
1111  getFeature2D_SURF_nOctaveLayers(),
1112  getFeature2D_SURF_extended(),
1113  getFeature2D_SURF_upright()));
1114  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1115  }
1116  }
1117 #endif
1118 #endif
1119 #if FINDOBJECT_TORCH == 1
1120  else if(strategies.at(index).compare("SuperPointTorch") == 0)
1121  {
1122  feature2D = new SuperPointTorch(
1123  getFeature2D_SuperPointTorch_modelPath(),
1124  getFeature2D_SuperPointTorch_threshold(),
1125  getFeature2D_SuperPointTorch_NMS(),
1126  getFeature2D_SuperPointTorch_NMS_radius(),
1127  getFeature2D_SuperPointTorch_cuda());
1128  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1129  }
1130 #endif
1131  }
1132  }
1133  }
1134 
1135  return feature2D;
1136 }
1137 
1139 {
1140  Feature2D * feature2D = 0;
1141  QString str = getFeature2D_2Descriptor();
1142  UDEBUG("Type=%s", str.toStdString().c_str());
1143  QStringList split = str.split(':');
1144  if(split.size()==2)
1145  {
1146  bool ok = false;
1147  int index = split.first().toInt(&ok);
1148  if(ok)
1149  {
1150  QStringList strategies = split.last().split(';');
1151  if(index>=0 && index<strategies.size())
1152  {
1153 
1154  //check for nonfree stuff
1155 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
1156 #if FINDOBJECT_NONFREE == 0
1157  if(strategies.at(index).compare("SIFT") == 0 ||
1158  strategies.at(index).compare("SURF") == 0)
1159  {
1160  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
1161  UERROR("Find-Object is not built with OpenCV nonfree module so "
1162  "SIFT/SURF cannot be used! Using default \"%s\" instead.",
1163  strategies.at(index).toStdString().c_str());
1164 
1165  }
1166 #endif
1167 #elif FINDOBJECT_NONFREE == 0 // >= 4.3.0
1168  if(strategies.at(index).compare("SURF") == 0)
1169  {
1170  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
1171  UERROR("Find-Object is not built with OpenCV nonfree module so "
1172  "SURF cannot be used! Using default \"%s\" instead.",
1173  strategies.at(index).toStdString().c_str());
1174 
1175  }
1176 #endif
1177 
1178 #if FINDOBJECT_TORCH == 0
1179  //check for nonfree stuff
1180  if(strategies.at(index).compare("SuperPointTorch") == 0)
1181  {
1182  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
1183  UERROR("Find-Object is not built with Torch so "
1184  "SuperPointTorch cannot be used! Using default \"%s\" instead.",
1185  strategies.at(index).toStdString().c_str());
1186 
1187  }
1188 #endif
1189 
1190 #if CV_MAJOR_VERSION < 3
1191  if(strategies.at(index).compare("KAZE") == 0 ||
1192  strategies.at(index).compare("AKAZE") == 0)
1193  {
1194  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
1195  UERROR("Find-Object is built with OpenCV 2 so "
1196  "KAZE/AKAZE cannot be used! Using default \"%s\" instead.",
1197  strategies.at(index).toStdString().c_str());
1198 
1199  }
1200 #else
1201 #ifndef HAVE_OPENCV_XFEATURES2D
1202  if(strategies.at(index).compare("Brief") == 0 ||
1203  strategies.at(index).compare("FREAK") == 0 ||
1204  strategies.at(index).compare("LUCID") == 0 ||
1205  strategies.at(index).compare("LATCH") == 0 ||
1206  strategies.at(index).compare("DAISY") == 0)
1207  {
1208  index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
1209  UERROR("Find-Object is not built with OpenCV xfeatures2d module so "
1210  "Brief/FREAK/LUCID/LATCH/DAISY cannot be used! Using default \"%s\" instead.",
1211  strategies.at(index).toStdString().c_str());
1212 
1213  }
1214 #endif
1215 #endif
1216 
1217  if(strategies.at(index).compare("Brief") == 0)
1218  {
1219 #if CV_MAJOR_VERSION < 3
1220  feature2D = new Feature2D(cv::Ptr<cv::DescriptorExtractor>(new cv::BriefDescriptorExtractor(
1221  getFeature2D_Brief_bytes())));
1222 #else
1223 #ifdef HAVE_OPENCV_XFEATURES2D
1224  feature2D = new Feature2D(cv::xfeatures2d::BriefDescriptorExtractor::create(
1225  getFeature2D_Brief_bytes()));
1226 #else
1227  UWARN("Find-Object is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1228 #endif
1229 #endif
1230  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1231  }
1232  else if(strategies.at(index).compare("ORB") == 0)
1233  {
1234  if(getFeature2D_ORB_gpu() && CVCUDA::getCudaEnabledDeviceCount())
1235  {
1236  feature2D = new GPUORB(
1237  getFeature2D_ORB_nFeatures(),
1238  getFeature2D_ORB_scaleFactor(),
1239  getFeature2D_ORB_nLevels(),
1240  getFeature2D_ORB_edgeThreshold(),
1241  getFeature2D_ORB_firstLevel(),
1242  getFeature2D_ORB_WTA_K(),
1243  getFeature2D_ORB_scoreType(),
1244  getFeature2D_ORB_patchSize(),
1245  getFeature2D_Fast_threshold(),
1246  getFeature2D_Fast_nonmaxSuppression());
1247  UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
1248  }
1249  else
1250  {
1251 #if CV_MAJOR_VERSION < 3
1252  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::ORB(
1253  getFeature2D_ORB_nFeatures(),
1254  getFeature2D_ORB_scaleFactor(),
1255  getFeature2D_ORB_nLevels(),
1256  getFeature2D_ORB_edgeThreshold(),
1257  getFeature2D_ORB_firstLevel(),
1258  getFeature2D_ORB_WTA_K(),
1259  getFeature2D_ORB_scoreType(),
1260  getFeature2D_ORB_patchSize())));
1261 #else
1262  feature2D = new Feature2D(cv::ORB::create(
1263  getFeature2D_ORB_nFeatures(),
1264  getFeature2D_ORB_scaleFactor(),
1265  getFeature2D_ORB_nLevels(),
1266  getFeature2D_ORB_edgeThreshold(),
1267  getFeature2D_ORB_firstLevel(),
1268  getFeature2D_ORB_WTA_K(),
1269 #if CV_MAJOR_VERSION > 3
1270  (cv::ORB::ScoreType)getFeature2D_ORB_scoreType(),
1271 #else
1272  getFeature2D_ORB_scoreType(),
1273 #endif
1274  getFeature2D_ORB_patchSize(),
1275  getFeature2D_Fast_threshold()));
1276 #endif
1277  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1278  }
1279  }
1280  else if(strategies.at(index).compare("BRISK") == 0)
1281  {
1282 #if CV_MAJOR_VERSION < 3
1283  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::BRISK(
1284  getFeature2D_BRISK_thresh(),
1285  getFeature2D_BRISK_octaves(),
1286  getFeature2D_BRISK_patternScale())));
1287 #else
1288  feature2D = new Feature2D(cv::BRISK::create(
1289  getFeature2D_BRISK_thresh(),
1290  getFeature2D_BRISK_octaves(),
1291  getFeature2D_BRISK_patternScale()));
1292 #endif
1293  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1294  }
1295  else if(strategies.at(index).compare("KAZE") == 0)
1296  {
1297 #if CV_MAJOR_VERSION < 3
1298  UWARN("Find-Object is not built with OpenCV 3 so KAZE cannot be used!");
1299 #else
1300  feature2D = new Feature2D(cv::KAZE::create(
1301  getFeature2D_KAZE_extended(),
1302  getFeature2D_KAZE_upright(),
1303  getFeature2D_KAZE_threshold(),
1304  getFeature2D_KAZE_nOctaves(),
1305  getFeature2D_KAZE_nOctaveLayers(),
1306  cv::KAZE::DIFF_PM_G2)); // FIXME: make a parameter
1307 #endif
1308  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1309  }
1310  else if(strategies.at(index).compare("AKAZE") == 0)
1311  {
1312 #if CV_MAJOR_VERSION < 3
1313  UWARN("Find-Object is not built with OpenCV 3 so AKAZE cannot be used!");
1314 #else
1315  feature2D = new Feature2D(cv::AKAZE::create(
1316  cv::AKAZE::DESCRIPTOR_MLDB, // FIXME: make a parameter
1317  getFeature2D_AKAZE_descriptorSize(),
1318  getFeature2D_AKAZE_descriptorChannels(),
1319  getFeature2D_AKAZE_threshold(),
1320  getFeature2D_AKAZE_nOctaves(),
1321  getFeature2D_AKAZE_nOctaveLayers(),
1322  cv::KAZE::DIFF_PM_G2)); // FIXME: make a parameter
1323 #endif
1324  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1325  }
1326  else if(strategies.at(index).compare("FREAK") == 0)
1327  {
1328 #if CV_MAJOR_VERSION < 3
1329  feature2D = new Feature2D(cv::Ptr<cv::DescriptorExtractor>(new cv::FREAK(
1330  getFeature2D_FREAK_orientationNormalized(),
1331  getFeature2D_FREAK_scaleNormalized(),
1332  getFeature2D_FREAK_patternScale(),
1333  getFeature2D_FREAK_nOctaves())));
1334 #else
1335 #ifdef HAVE_OPENCV_XFEATURES2D
1336  feature2D = new Feature2D(cv::xfeatures2d::FREAK::create(
1337  getFeature2D_FREAK_orientationNormalized(),
1338  getFeature2D_FREAK_scaleNormalized(),
1339  getFeature2D_FREAK_patternScale(),
1340  getFeature2D_FREAK_nOctaves()));
1341 #else
1342  UWARN("Find-Object is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1343 #endif
1344 #endif
1345 
1346  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1347  }
1348 #ifdef HAVE_OPENCV_XFEATURES2D
1349  else if(strategies.at(index).compare("LUCID") == 0)
1350  {
1351  feature2D = new Feature2D(cv::xfeatures2d::LUCID::create(
1352  getFeature2D_LUCID_kernel(),
1353  getFeature2D_LUCID_blur_kernel()));
1354 
1355  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1356  }
1357  else if(strategies.at(index).compare("LATCH") == 0)
1358  {
1359  feature2D = new Feature2D(cv::xfeatures2d::LATCH::create(
1360  getFeature2D_LATCH_bytes(),
1361  getFeature2D_LATCH_rotationInvariance(),
1362  getFeature2D_LATCH_half_ssd_size()));
1363 
1364  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1365  }
1366  else if(strategies.at(index).compare("DAISY") == 0)
1367  {
1368  feature2D = new Feature2D(cv::xfeatures2d::DAISY::create(
1369  getFeature2D_DAISY_radius(),
1370  getFeature2D_DAISY_q_radius(),
1371  getFeature2D_DAISY_q_theta(),
1372  getFeature2D_DAISY_q_hist(),
1373  cv::xfeatures2d::DAISY::NRM_NONE,
1374  cv::noArray(),
1375  getFeature2D_DAISY_interpolation(),
1376  getFeature2D_DAISY_use_orientation()));
1377 
1378  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1379  }
1380 #endif
1381 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
1382 #if FINDOBJECT_NONFREE == 1
1383  else if(strategies.at(index).compare("SIFT") == 0)
1384  {
1385 #if CV_MAJOR_VERSION < 3
1386  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::SIFT(
1387  getFeature2D_SIFT_nfeatures(),
1388  getFeature2D_SIFT_nOctaveLayers(),
1389  getFeature2D_SIFT_contrastThreshold(),
1390  getFeature2D_SIFT_edgeThreshold(),
1391  getFeature2D_SIFT_sigma())));
1392 #else
1393  feature2D = new Feature2D(cv::xfeatures2d::SIFT::create(
1394  getFeature2D_SIFT_nfeatures(),
1395  getFeature2D_SIFT_nOctaveLayers(),
1396  getFeature2D_SIFT_contrastThreshold(),
1397  getFeature2D_SIFT_edgeThreshold(),
1398  getFeature2D_SIFT_sigma()));
1399 #endif
1400  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1401  }
1402  else if(strategies.at(index).compare("SURF") == 0)
1403  {
1404  if(getFeature2D_SURF_gpu() && CVCUDA::getCudaEnabledDeviceCount())
1405  {
1406  feature2D = new GPUSURF(
1407  getFeature2D_SURF_hessianThreshold(),
1408  getFeature2D_SURF_nOctaves(),
1409  getFeature2D_SURF_nOctaveLayers(),
1410  getFeature2D_SURF_extended(),
1411  getFeature2D_SURF_keypointsRatio(),
1412  getFeature2D_SURF_upright());
1413  UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
1414  }
1415  else
1416  {
1417 #if CV_MAJOR_VERSION < 3
1418  feature2D = new Feature2D(cv::Ptr<cv::Feature2D>(new cv::SURF(
1419  getFeature2D_SURF_hessianThreshold(),
1420  getFeature2D_SURF_nOctaves(),
1421  getFeature2D_SURF_nOctaveLayers(),
1422  getFeature2D_SURF_extended(),
1423  getFeature2D_SURF_upright())));
1424 #else
1425  feature2D = new Feature2D(cv::xfeatures2d::SURF::create(
1426  getFeature2D_SURF_hessianThreshold(),
1427  getFeature2D_SURF_nOctaves(),
1428  getFeature2D_SURF_nOctaveLayers(),
1429  getFeature2D_SURF_extended(),
1430  getFeature2D_SURF_upright()));
1431 #endif
1432  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1433  }
1434  }
1435 #endif
1436 #else // >= 4.3.0-dev
1437  else if(strategies.at(index).compare("SIFT") == 0)
1438  {
1439  feature2D = new Feature2D(cv::SIFT::create(
1440  getFeature2D_SIFT_nfeatures(),
1441  getFeature2D_SIFT_nOctaveLayers(),
1442  getFeature2D_SIFT_contrastThreshold(),
1443  getFeature2D_SIFT_edgeThreshold(),
1444  getFeature2D_SIFT_sigma()));
1445  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1446  }
1447 #if FINDOBJECT_NONFREE == 1
1448  else if(strategies.at(index).compare("SURF") == 0)
1449  {
1450  if(getFeature2D_SURF_gpu() && CVCUDA::getCudaEnabledDeviceCount())
1451  {
1452  feature2D = new GPUSURF(
1453  getFeature2D_SURF_hessianThreshold(),
1454  getFeature2D_SURF_nOctaves(),
1455  getFeature2D_SURF_nOctaveLayers(),
1456  getFeature2D_SURF_extended(),
1457  getFeature2D_SURF_keypointsRatio(),
1458  getFeature2D_SURF_upright());
1459  UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
1460  }
1461  else
1462  {
1463  feature2D = new Feature2D(cv::xfeatures2d::SURF::create(
1464  getFeature2D_SURF_hessianThreshold(),
1465  getFeature2D_SURF_nOctaves(),
1466  getFeature2D_SURF_nOctaveLayers(),
1467  getFeature2D_SURF_extended(),
1468  getFeature2D_SURF_upright()));
1469  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1470  }
1471  }
1472 #endif
1473 #endif
1474 
1475 #if FINDOBJECT_TORCH == 1
1476  else if(strategies.at(index).compare("SuperPointTorch") == 0)
1477  {
1478  feature2D = new SuperPointTorch(
1479  getFeature2D_SuperPointTorch_modelPath(),
1480  getFeature2D_SuperPointTorch_threshold(),
1481  getFeature2D_SuperPointTorch_NMS(),
1482  getFeature2D_SuperPointTorch_NMS_radius(),
1483  getFeature2D_SuperPointTorch_cuda());
1484  UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
1485  }
1486 #endif
1487  }
1488  }
1489  }
1490 
1491  return feature2D;
1492 }
1493 
1495 {
1496  int index = getFeature2D_1Detector().split(':').first().toInt();
1497  return getFeature2D_1Detector().split(':').last().split(';').at(index);
1498 }
1499 
1501 {
1502  int index = getFeature2D_2Descriptor().split(':').first().toInt();
1503  return getFeature2D_2Descriptor().split(':').last().split(';').at(index);
1504 }
1505 
1507 {
1508  int index = getNearestNeighbor_1Strategy().split(':').first().toInt();
1509  return getNearestNeighbor_1Strategy().split(':').last().split(';').at(index);
1510 }
1511 
1513 {
1514  bool bruteForce = false;
1515  QString str = getNearestNeighbor_1Strategy();
1516  QStringList split = str.split(':');
1517  if(split.size()==2)
1518  {
1519  bool ok = false;
1520  int index = split.first().toInt(&ok);
1521  if(ok)
1522  {
1523  QStringList strategies = split.last().split(';');
1524  if(strategies.size() >= 7 && index == 6)
1525  {
1526  bruteForce = true;
1527  }
1528  }
1529  }
1530  return bruteForce;
1531 }
1532 
1533 cv::flann::IndexParams * Settings::createFlannIndexParams()
1534 {
1535  cv::flann::IndexParams * params = 0;
1536  QString str = getNearestNeighbor_1Strategy();
1537  QStringList split = str.split(':');
1538  if(split.size()==2)
1539  {
1540  bool ok = false;
1541  int index = split.first().toInt(&ok);
1542  if(ok)
1543  {
1544  QStringList strategies = split.last().split(';');
1545  if(strategies.size() >= 6 && index>=0 && index<6)
1546  {
1547  switch(index)
1548  {
1549  case 0:
1550  if(strategies.at(index).compare("Linear") == 0)
1551  {
1552  UDEBUG("type=%s", "Linear");
1553  params = new cv::flann::LinearIndexParams();
1554  }
1555  break;
1556  case 1:
1557  if(strategies.at(index).compare("KDTree") == 0)
1558  {
1559  UDEBUG("type=%s", "KDTree");
1560  params = new cv::flann::KDTreeIndexParams(
1561  getNearestNeighbor_KDTree_trees());
1562  }
1563  break;
1564  case 2:
1565  if(strategies.at(index).compare("KMeans") == 0)
1566  {
1567  cvflann::flann_centers_init_t centers_init = cvflann::FLANN_CENTERS_RANDOM;
1568  QString str = getNearestNeighbor_KMeans_centers_init();
1569  QStringList split = str.split(':');
1570  if(split.size()==2)
1571  {
1572  bool ok = false;
1573  int index = split.first().toInt(&ok);
1574  if(ok)
1575  {
1576  centers_init = (cvflann::flann_centers_init_t)index;
1577  }
1578  }
1579  UDEBUG("type=%s", "KMeans");
1580  params = new cv::flann::KMeansIndexParams(
1581  getNearestNeighbor_KMeans_branching(),
1582  getNearestNeighbor_KMeans_iterations(),
1583  centers_init,
1584  getNearestNeighbor_KMeans_cb_index());
1585  }
1586  break;
1587  case 3:
1588  if(strategies.at(index).compare("Composite") == 0)
1589  {
1590  cvflann::flann_centers_init_t centers_init = cvflann::FLANN_CENTERS_RANDOM;
1591  QString str = getNearestNeighbor_Composite_centers_init();
1592  QStringList split = str.split(':');
1593  if(split.size()==2)
1594  {
1595  bool ok = false;
1596  int index = split.first().toInt(&ok);
1597  if(ok)
1598  {
1599  centers_init = (cvflann::flann_centers_init_t)index;
1600  }
1601  }
1602  UDEBUG("type=%s", "Composite");
1603  params = new cv::flann::CompositeIndexParams(
1604  getNearestNeighbor_Composite_trees(),
1605  getNearestNeighbor_Composite_branching(),
1606  getNearestNeighbor_Composite_iterations(),
1607  centers_init,
1608  getNearestNeighbor_Composite_cb_index());
1609  }
1610  break;
1611  case 4:
1612  if(strategies.at(index).compare("Autotuned") == 0)
1613  {
1614  UDEBUG("type=%s", "Autotuned");
1615  params = new cv::flann::AutotunedIndexParams(
1616  getNearestNeighbor_Autotuned_target_precision(),
1617  getNearestNeighbor_Autotuned_build_weight(),
1618  getNearestNeighbor_Autotuned_memory_weight(),
1619  getNearestNeighbor_Autotuned_sample_fraction());
1620  }
1621  break;
1622  case 5:
1623  if(strategies.at(index).compare("Lsh") == 0)
1624  {
1625  UDEBUG("type=%s", "Lsh");
1626  params = new cv::flann::LshIndexParams(
1627  getNearestNeighbor_Lsh_table_number(),
1628  getNearestNeighbor_Lsh_key_size(),
1629  getNearestNeighbor_Lsh_multi_probe_level());
1630 
1631  }
1632  break;
1633  default:
1634  break;
1635  }
1636  }
1637  }
1638  }
1639  if(!params)
1640  {
1641  UERROR("NN strategy not found !? Using default KDTRee...");
1642  params = new cv::flann::KDTreeIndexParams();
1643  }
1644  return params ;
1645 }
1646 
1647 cvflann::flann_distance_t Settings::getFlannDistanceType()
1648 {
1649  cvflann::flann_distance_t distance = cvflann::FLANN_DIST_L2;
1650  QString str = getNearestNeighbor_2Distance_type();
1651  QStringList split = str.split(':');
1652  if(split.size()==2)
1653  {
1654  bool ok = false;
1655  int index = split.first().toInt(&ok);
1656  if(ok)
1657  {
1658  QStringList strategies = split.last().split(';');
1659  if(strategies.size() == 9 && index>=0 && index<=8)
1660  {
1661  distance = (cvflann::flann_distance_t)(index+1);
1662  }
1663  }
1664  }
1665  return distance;
1666 }
1667 
1669 {
1670  int method = cv::RANSAC;
1671  QString str = getHomography_method();
1672  QStringList split = str.split(':');
1673  if(split.size()==2)
1674  {
1675  bool ok = false;
1676  int index = split.first().toInt(&ok);
1677  if(ok)
1678  {
1679  QStringList strategies = split.last().split(';');
1680  if(strategies.size() == 2 && index>=0 && index<2)
1681  {
1682  switch(method)
1683  {
1684 #if CV_MAJOR_VERSION >= 3
1685  case 2:
1686  method = cv::RHO;
1687  break;
1688 #endif
1689  case 0:
1690  method = cv::LMEDS;
1691  break;
1692  default:
1693  method = cv::RANSAC;
1694  break;
1695  }
1696  }
1697  }
1698  }
1699  UDEBUG("method=%d", method);
1700  return method;
1701 }
1702 
1703 #if CV_MAJOR_VERSION < 3
1704 Feature2D::Feature2D(cv::Ptr<cv::FeatureDetector> featureDetector) :
1705  featureDetector_(featureDetector)
1706 {
1707  UASSERT(!featureDetector_.empty());
1708 }
1709 Feature2D::Feature2D(cv::Ptr<cv::DescriptorExtractor> descriptorExtractor) :
1710  descriptorExtractor_(descriptorExtractor)
1711 {
1712  UASSERT(!descriptorExtractor_.empty());
1713 }
1714 #endif
1715 Feature2D::Feature2D(cv::Ptr<cv::Feature2D> feature2D) :
1716  feature2D_(feature2D)
1717 {
1718  UASSERT(!feature2D_.empty());
1719 }
1720 
1721 void Feature2D::detect(const cv::Mat & image,
1722  std::vector<cv::KeyPoint> & keypoints,
1723  const cv::Mat & mask)
1724 {
1725 #if CV_MAJOR_VERSION < 3
1726  if(!featureDetector_.empty())
1727  {
1728  featureDetector_->detect(image, keypoints, mask);
1729  }
1730  else
1731 #endif
1732  if(!feature2D_.empty())
1733  {
1734  feature2D_->detect(image, keypoints, mask);
1735  }
1736  else
1737  {
1738  UERROR("Feature2D not set!?!?");
1739  }
1740 }
1741 
1742 void Feature2D::compute(const cv::Mat & image,
1743  std::vector<cv::KeyPoint> & keypoints,
1744  cv::Mat & descriptors)
1745 {
1746 #if CV_MAJOR_VERSION < 3
1747  if(!descriptorExtractor_.empty())
1748  {
1749  descriptorExtractor_->compute(image, keypoints, descriptors);
1750  }
1751  else
1752 #endif
1753  if(!feature2D_.empty())
1754  {
1755  feature2D_->compute(image, keypoints, descriptors);
1756  }
1757  else
1758  {
1759  UERROR("Feature2D not set!?!?");
1760  }
1761 }
1762 
1763 void Feature2D::detectAndCompute(const cv::Mat & image,
1764  std::vector<cv::KeyPoint> & keypoints,
1765  cv::Mat & descriptors,
1766  const cv::Mat & mask)
1767 {
1768  if(!feature2D_.empty())
1769  {
1770 #if CV_MAJOR_VERSION < 3
1771  (*feature2D_)(image, mask, keypoints, descriptors);
1772 #else
1773  feature2D_->detectAndCompute(image, mask, keypoints, descriptors);
1774 #endif
1775  }
1776  else
1777  {
1778  UERROR("Cannot use Feature2D::detectAndCompute() if feature2D member is not set.");
1779  }
1780 }
1781 
1782 } // namespace find_object
d
static QString iniDefaultPath()
Definition: Settings.cpp:83
static cv::flann::IndexParams * createFlannIndexParams()
Definition: Settings.cpp:1533
static int getHomographyMethod()
Definition: Settings.cpp:1668
GPUORB(int nFeatures=Settings::defaultFeature2D_ORB_nFeatures(), float scaleFactor=Settings::defaultFeature2D_ORB_scaleFactor(), int nLevels=Settings::defaultFeature2D_ORB_nLevels(), int edgeThreshold=Settings::defaultFeature2D_ORB_edgeThreshold(), int firstLevel=Settings::defaultFeature2D_ORB_firstLevel(), int WTA_K=Settings::defaultFeature2D_ORB_WTA_K(), int scoreType=Settings::defaultFeature2D_ORB_scoreType(), int patchSize=Settings::defaultFeature2D_ORB_patchSize(), int fastThreshold=Settings::defaultFeature2D_Fast_threshold(), bool fastNonmaxSupression=Settings::defaultFeature2D_Fast_nonmaxSuppression())
Definition: Settings.cpp:519
static Feature2D * createKeypointDetector()
Definition: Settings.cpp:722
static QVariant getParameter(const QString &key)
Definition: Settings.h:343
CVCUDA::FAST_GPU fast_
Definition: Settings.cpp:508
virtual void detectAndCompute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:1763
static const ParametersType & getParametersType()
Definition: Settings.h:339
CVCUDA::ORB_GPU orb_
Definition: Settings.cpp:671
cv::Ptr< cv::FeatureDetector > featureDetector_
Definition: Settings.h:396
static ParametersType parametersType_
Definition: Settings.h:364
GPUFAST(int threshold=Settings::defaultFeature2D_Fast_threshold(), bool nonmaxSuppression=Settings::defaultFeature2D_Fast_nonmaxSuppression(), double keypointsRatio=Settings::defaultFeature2D_Fast_keypointsRatio())
Definition: Settings.cpp:455
static cvflann::flann_distance_t getFlannDistanceType()
Definition: Settings.cpp:1647
static void loadWindowSettings(QByteArray &windowGeometry, QByteArray &windowState, const QString &fileName=QString())
Definition: Settings.cpp:260
#define UASSERT(condition)
static QString currentDetectorType()
Definition: Settings.cpp:1494
#define CVCUDA
Definition: Settings.cpp:41
static DescriptionsMap descriptions_
Definition: Settings.h:365
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:476
static QString iniPath_
Definition: Settings.h:367
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
Definition: Settings.cpp:492
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:1721
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:560
ROSCPP_DECL bool ok()
QMap< QString, QString > ParametersType
Definition: Settings.h:44
static void setParameter(const QString &key, const QVariant &value)
Definition: Settings.h:341
QMap< QString, QVariant > ParametersMap
Definition: Settings.h:41
static QString currentDescriptorType()
Definition: Settings.cpp:1500
static ParametersMap parameters_
Definition: Settings.h:363
static Settings dummyInit_
Definition: Settings.h:366
static ParametersMap loadSettings(const QString &fileName=QString())
Definition: Settings.cpp:107
virtual void detectAndCompute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:628
QMap< QString, QString > DescriptionsMap
Definition: Settings.h:45
static void saveWindowSettings(const QByteArray &windowGeometry, const QByteArray &windowState, const QString &fileName=QString())
Definition: Settings.cpp:314
static QString workingDirectory()
Definition: Settings.cpp:74
static QString currentNearestNeighborType()
Definition: Settings.cpp:1506
static bool isBruteForceNearestNeighbor()
Definition: Settings.cpp:1512
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
Definition: Settings.cpp:1742
#define UDEBUG(...)
static QString iniDefaultFileName()
Definition: Settings.h:327
#define UERROR(...)
ULogger class and convenient macros.
#define UWARN(...)
static QString iniPath()
Definition: Settings.cpp:92
static Feature2D * createDescriptorExtractor()
Definition: Settings.cpp:1138
static ParametersMap defaultParameters_
Definition: Settings.h:362
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
Definition: Settings.cpp:589
cv::Ptr< cv::DescriptorExtractor > descriptorExtractor_
Definition: Settings.h:397
cv::Ptr< cv::Feature2D > feature2D_
Definition: Settings.h:399
virtual void detectAndCompute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:498
static ParametersMap init(const QString &fileName)
Definition: Settings.cpp:101
static void saveSettings(const QString &fileName=QString())
Definition: Settings.cpp:288
#define UINFO(...)


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:09