32 #include <QtCore/QSettings> 33 #include <QtCore/QStringList> 34 #include <QtCore/QDir> 36 #include <opencv2/calib3d/calib3d.hpp> 37 #include <opencv2/opencv_modules.hpp> 39 #if CV_MAJOR_VERSION < 3 40 #include <opencv2/gpu/gpu.hpp> 41 #define CVCUDA cv::gpu 43 #include <opencv2/core/cuda.hpp> 44 #define CVCUDA cv::cuda 45 #ifdef HAVE_OPENCV_CUDAFEATURES2D 46 #include <opencv2/cudafeatures2d.hpp> 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> 56 #ifdef HAVE_OPENCV_XFEATURES2D 57 #include <opencv2/xfeatures2d.hpp> 58 #include <opencv2/xfeatures2d/cuda.hpp> 73 return QString(
"%1/Documents/%2").arg(QDir::homePath()).arg(PROJECT_NAME);
75 return QString(
"%1").arg(QDir::homePath());
105 QString path = fileName;
106 if(fileName.isEmpty())
112 QSettings ini(path, QSettings::IniFormat);
115 const QString & key = iter.key();
116 QVariant value = ini.value(key, QVariant());
119 QString str = value.toString();
120 if(str.contains(
";"))
126 QChar index = str.at(0);
128 str[0] = index.toLatin1();
129 value = QVariant(str);
130 UINFO(
"Updated list of parameter \"%s\"", key.toStdString().c_str());
132 #if FINDOBJECT_NONFREE == 0 133 QChar index = str.at(0);
134 if(key.compare(Settings::kFeature2D_1Detector()) == 0)
136 if(index ==
'5' || index ==
'7')
138 index = Settings::defaultFeature2D_1Detector().at(0);
139 int indexInt = Settings::defaultFeature2D_1Detector().split(
':').first().toInt();
140 UWARN(
"Trying to set \"%s\" to SIFT/SURF but Find-Object isn't built " 141 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
142 Settings::kFeature2D_1Detector().toStdString().c_str(),
143 Settings::defaultFeature2D_1Detector().split(
':').last().split(
";").at(indexInt).toStdString().c_str());
146 else if(key.compare(Settings::kFeature2D_2Descriptor()) == 0)
148 if(index ==
'2' || index ==
'3')
150 index = Settings::defaultFeature2D_2Descriptor().at(0);
151 int indexInt = Settings::defaultFeature2D_2Descriptor().split(
':').first().toInt();
152 UWARN(
"Trying to set \"%s\" to SIFT/SURF but Find-Object isn't built " 153 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
154 Settings::kFeature2D_2Descriptor().toStdString().c_str(),
155 Settings::defaultFeature2D_2Descriptor().split(
':').last().split(
";").at(indexInt).toStdString().c_str());
158 else if(key.compare(Settings::kNearestNeighbor_1Strategy()) == 0)
162 index = Settings::defaultNearestNeighbor_1Strategy().at(0);
163 int indexInt = Settings::defaultNearestNeighbor_1Strategy().split(
':').first().toInt();
164 UWARN(
"Trying to set \"%s\" to one FLANN approach but Find-Object isn't built " 165 "with the nonfree module from OpenCV and FLANN cannot be used " 166 "with binary descriptors. Keeping default combo value: %s.",
167 Settings::kNearestNeighbor_1Strategy().toStdString().c_str(),
168 Settings::defaultNearestNeighbor_1Strategy().split(
':').last().split(
";").at(indexInt).toStdString().c_str());
172 str[0] = index.toLatin1();
173 value = QVariant(str);
179 UINFO(
"Settings loaded from %s.", path.toStdString().c_str());
184 UINFO(
"Settings set to defaults.");
187 if(CVCUDA::getCudaEnabledDeviceCount() == 0)
189 #if FINDOBJECT_NONFREE == 1 190 Settings::setFeature2D_SURF_gpu(
false);
192 Settings::setFeature2D_Fast_gpu(
false);
193 Settings::setFeature2D_ORB_gpu(
false);
194 Settings::setNearestNeighbor_BruteForce_gpu(
false);
200 QString path = fileName;
201 if(fileName.isEmpty())
208 QSettings ini(path, QSettings::IniFormat);
210 QVariant value = ini.value(
"windowGeometry", QVariant());
213 windowGeometry = value.toByteArray();
216 value = ini.value(
"windowState", QVariant());
219 windowState = value.toByteArray();
222 UINFO(
"Window settings loaded from %s", path.toStdString().c_str());
228 QString path = fileName;
229 if(fileName.isEmpty())
235 QSettings ini(path, QSettings::IniFormat);
239 if(type.compare(
"float") == 0)
241 ini.setValue(iter.key(), QString::number(iter.value().toFloat(),
'g',6));
245 ini.setValue(iter.key(), iter.value());
248 UINFO(
"Settings saved to %s", path.toStdString().c_str());
254 QString path = fileName;
255 if(fileName.isEmpty())
261 QSettings ini(path, QSettings::IniFormat);
262 if(!windowGeometry.isEmpty())
264 ini.setValue(
"windowGeometry", windowGeometry);
266 if(!windowState.isEmpty())
268 ini.setValue(
"windowState", windowState);
270 UINFO(
"Window settings saved to %s", path.toStdString().c_str());
274 #if FINDOBJECT_NONFREE == 1 278 GPUSURF(
double hessianThreshold,
282 float keypointsRatio,
284 surf_(hessianThreshold,
292 virtual ~GPUSURF() {}
294 virtual void detect(
const cv::Mat & image,
295 std::vector<cv::KeyPoint> & keypoints,
296 const cv::Mat & mask = cv::Mat())
298 CVCUDA::GpuMat imgGpu(image);
299 CVCUDA::GpuMat maskGpu(mask);
302 surf_(imgGpu, maskGpu, keypoints);
304 catch(cv::Exception &e)
306 UERROR(
"GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF " 307 "is too high for the size of the image (%d,%d).)",
315 virtual void compute(
const cv::Mat& image,
316 std::vector<cv::KeyPoint>& keypoints,
317 cv::Mat& descriptors)
319 std::vector<float>
d;
320 CVCUDA::GpuMat imgGpu(image);
321 CVCUDA::GpuMat descriptorsGPU;
324 surf_(imgGpu, CVCUDA::GpuMat(), keypoints, descriptorsGPU,
true);
326 catch(cv::Exception &e)
328 UERROR(
"GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF " 329 "is too high for the size of the image (%d,%d).)",
337 if (descriptorsGPU.empty())
338 descriptors = cv::Mat();
341 UASSERT(descriptorsGPU.type() == CV_32F);
342 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
343 descriptorsGPU.download(descriptors);
347 virtual void detectAndCompute(
const cv::Mat& image,
348 std::vector<cv::KeyPoint>& keypoints,
349 cv::Mat& descriptors,
350 const cv::Mat & mask = cv::Mat())
352 std::vector<float>
d;
353 CVCUDA::GpuMat imgGpu(image);
354 CVCUDA::GpuMat descriptorsGPU;
355 CVCUDA::GpuMat maskGpu(mask);
358 surf_(imgGpu, maskGpu, keypoints, descriptorsGPU,
false);
360 catch(cv::Exception &e)
362 UERROR(
"GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF " 363 "is too high for the size of the image (%d,%d).)",
371 if (descriptorsGPU.empty())
372 descriptors = cv::Mat();
375 UASSERT(descriptorsGPU.type() == CV_32F);
376 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
377 descriptorsGPU.download(descriptors);
382 #if CV_MAJOR_VERSION < 3 383 CVCUDA::SURF_GPU surf_;
385 CVCUDA::SURF_CUDA surf_;
393 GPUFAST(
int threshold=Settings::defaultFeature2D_Fast_threshold(),
394 bool nonmaxSuppression=Settings::defaultFeature2D_Fast_nonmaxSuppression(),
395 #
if CV_MAJOR_VERSION < 3
396 double keypointsRatio=Settings::defaultFeature2D_Fast_keypointsRatio())
401 int max_npoints=
Settings::defaultFeature2D_Fast_maxNpoints())
402 #ifdef HAVE_OPENCV_CUDAFEATURES2D
403 : fast_(
CVCUDA::FastFeatureDetector::create(
406 CVCUDA::FastFeatureDetector::TYPE_9_16,
414 virtual void detect(
const cv::Mat & image,
415 std::vector<cv::KeyPoint> & keypoints,
416 const cv::Mat & mask = cv::Mat())
418 CVCUDA::GpuMat imgGpu(image);
419 CVCUDA::GpuMat maskGpu(mask);
420 #if CV_MAJOR_VERSION < 3 421 fast_(imgGpu, maskGpu, keypoints);
423 #ifdef HAVE_OPENCV_CUDAFEATURES2D 424 CVCUDA::GpuMat keypointsGpu(keypoints);
425 fast_->detectAsync(imgGpu, keypointsGpu, maskGpu);
426 fast_->convert(keypointsGpu, keypoints);
431 std::vector<cv::KeyPoint>& keypoints,
432 cv::Mat& descriptors)
434 UERROR(
"GPUFAST:computeDescriptors() Should not be used!");
437 std::vector<cv::KeyPoint>& keypoints,
438 cv::Mat& descriptors,
439 const cv::Mat & mask = cv::Mat())
441 UERROR(
"GPUFAST:detectAndCompute() Should not be used!");
445 #if CV_MAJOR_VERSION < 3 448 #ifdef HAVE_OPENCV_CUDAFEATURES2D 449 cv::Ptr<CVCUDA::FastFeatureDetector> fast_;
457 GPUORB(
int nFeatures = Settings::defaultFeature2D_ORB_nFeatures(),
458 float scaleFactor = Settings::defaultFeature2D_ORB_scaleFactor(),
459 int nLevels = Settings::defaultFeature2D_ORB_nLevels(),
460 int edgeThreshold = Settings::defaultFeature2D_ORB_edgeThreshold(),
461 int firstLevel = Settings::defaultFeature2D_ORB_firstLevel(),
462 int WTA_K = Settings::defaultFeature2D_ORB_WTA_K(),
463 int scoreType = Settings::defaultFeature2D_ORB_scoreType(),
464 int patchSize = Settings::defaultFeature2D_ORB_patchSize(),
465 int fastThreshold = Settings::defaultFeature2D_Fast_threshold(),
466 #
if CV_MAJOR_VERSION < 3
467 bool fastNonmaxSupression = Settings::defaultFeature2D_Fast_nonmaxSuppression())
477 bool blurForDescriptor =
Settings::defaultFeature2D_ORB_blurForDescriptor())
478 #ifdef HAVE_OPENCV_CUDAFEATURES2D
479 : orb_(
CVCUDA::ORB::create(nFeatures,
492 #if CV_MAJOR_VERSION < 3 493 orb_.setFastParams(fastThreshold, fastNonmaxSupression);
498 virtual void detect(
const cv::Mat & image,
499 std::vector<cv::KeyPoint> & keypoints,
500 const cv::Mat & mask = cv::Mat())
503 CVCUDA::GpuMat imgGpu(image);
504 CVCUDA::GpuMat maskGpu(mask);
508 #if CV_MAJOR_VERSION < 3 509 orb_(imgGpu, maskGpu, keypoints);
511 #ifdef HAVE_OPENCV_CUDAFEATURES2D 512 CVCUDA::GpuMat keypointsGpu;
513 orb_->detectAsync(imgGpu, keypointsGpu, maskGpu);
514 orb_->convert(keypointsGpu, keypoints);
518 catch(cv::Exception &e)
520 UERROR(
"GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
528 std::vector<cv::KeyPoint>& keypoints,
529 cv::Mat& descriptors)
531 std::vector<float>
d;
533 CVCUDA::GpuMat imgGpu(image);
534 CVCUDA::GpuMat descriptorsGPU;
538 #if CV_MAJOR_VERSION < 3 539 orb_(imgGpu, CVCUDA::GpuMat(), keypoints, descriptorsGPU);
541 #ifdef HAVE_OPENCV_CUDAFEATURES2D 542 UERROR(
"OpenCV 3 ORB-GPU doesn't support extracting ORB descriptors from already extracted keypoints. " 543 "Use ORB as feature detector too or desactivate ORB-GPU.");
548 catch(cv::Exception &e)
550 UERROR(
"GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
556 if (descriptorsGPU.empty())
557 descriptors = cv::Mat();
560 UASSERT(descriptorsGPU.type() == CV_8U);
561 descriptors = cv::Mat(descriptorsGPU.size(), CV_8U);
562 descriptorsGPU.download(descriptors);
567 std::vector<cv::KeyPoint>& keypoints,
568 cv::Mat& descriptors,
569 const cv::Mat & mask = cv::Mat())
571 std::vector<float>
d;
573 CVCUDA::GpuMat imgGpu(image);
574 CVCUDA::GpuMat descriptorsGPU;
575 CVCUDA::GpuMat maskGpu(mask);
579 #if CV_MAJOR_VERSION < 3 580 orb_(imgGpu, CVCUDA::GpuMat(), keypoints, descriptorsGPU);
582 #ifdef HAVE_OPENCV_CUDAFEATURES2D 583 CVCUDA::GpuMat keypointsGpu;
584 orb_->detectAndComputeAsync(imgGpu, maskGpu, keypointsGpu, descriptorsGPU,
false);
585 orb_->convert(keypointsGpu, keypoints);
589 catch(cv::Exception &e)
591 UERROR(
"GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
597 if (descriptorsGPU.empty())
598 descriptors = cv::Mat();
601 UASSERT(descriptorsGPU.type() == CV_8U);
602 descriptors = cv::Mat(descriptorsGPU.size(), CV_8U);
603 descriptorsGPU.download(descriptors);
608 #if CV_MAJOR_VERSION < 3 611 #ifdef HAVE_OPENCV_CUDAFEATURES2D 612 cv::Ptr<CVCUDA::ORB> orb_;
620 QString str = getFeature2D_1Detector();
621 QStringList split = str.split(
':');
625 int index = split.first().toInt(&ok);
628 QStringList strategies = split.last().split(
';');
630 if(index>=0 && index<strategies.size())
633 #if FINDOBJECT_NONFREE == 0 635 if(strategies.at(index).compare(
"SIFT") == 0 ||
636 strategies.at(index).compare(
"SURF") == 0)
638 index = Settings::defaultFeature2D_1Detector().split(
':').first().toInt();
639 UERROR(
"Find-Object is not built with OpenCV nonfree module so " 640 "SIFT/SURF cannot be used! Using default \"%s\" instead.",
641 strategies.at(index).toStdString().c_str());
646 #if CV_MAJOR_VERSION < 3 647 if(strategies.at(index).compare(
"AGAST") == 0 ||
648 strategies.at(index).compare(
"KAZE") == 0 ||
649 strategies.at(index).compare(
"AKAZE") == 0)
651 index = Settings::defaultFeature2D_1Detector().split(
':').first().toInt();
652 UERROR(
"Find-Object is built with OpenCV 2 so " 653 "AGAST/KAZE/AKAZE cannot be used! Using default \"%s\" instead.",
654 strategies.at(index).toStdString().c_str());
658 if(strategies.at(index).compare(
"Dense") == 0)
660 index = Settings::defaultFeature2D_1Detector().split(
':').first().toInt();
661 UERROR(
"Find-Object is built with OpenCV 3 so " 662 "Dense cannot be used! Using default \"%s\" instead.",
663 strategies.at(index).toStdString().c_str());
666 #ifndef HAVE_OPENCV_XFEATURES2D 667 if(strategies.at(index).compare(
"Star") == 0)
669 index = Settings::defaultFeature2D_1Detector().split(
':').first().toInt();
670 UERROR(
"Find-Object is not built with OpenCV xfeatures2d module so " 671 "Star cannot be used! Using default \"%s\" instead.",
672 strategies.at(index).toStdString().c_str());
678 if(strategies.at(index).compare(
"Dense") == 0)
680 #if CV_MAJOR_VERSION < 3 681 feature2D =
new Feature2D(cv::Ptr<cv::FeatureDetector>(
new cv::DenseFeatureDetector(
682 getFeature2D_Dense_initFeatureScale(),
683 getFeature2D_Dense_featureScaleLevels(),
684 getFeature2D_Dense_featureScaleMul(),
685 getFeature2D_Dense_initXyStep(),
686 getFeature2D_Dense_initImgBound(),
687 getFeature2D_Dense_varyXyStepWithScale(),
688 getFeature2D_Dense_varyImgBoundWithScale())));
690 UWARN(
"Find-Object is not built with OpenCV 2 so Dense cannot be used!");
692 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
694 else if(strategies.at(index).compare(
"Fast") == 0)
696 if(getFeature2D_Fast_gpu() && CVCUDA::getCudaEnabledDeviceCount())
699 getFeature2D_Fast_threshold(),
700 getFeature2D_Fast_nonmaxSuppression());
701 UDEBUG(
"type=%s GPU", strategies.at(index).toStdString().c_str());
705 #if CV_MAJOR_VERSION < 3 706 feature2D =
new Feature2D(cv::Ptr<cv::FeatureDetector>(
new cv::FastFeatureDetector(
707 getFeature2D_Fast_threshold(),
708 getFeature2D_Fast_nonmaxSuppression())));
710 feature2D =
new Feature2D(cv::FastFeatureDetector::create(
711 getFeature2D_Fast_threshold(),
712 getFeature2D_Fast_nonmaxSuppression()));
714 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
717 else if(strategies.at(index).compare(
"AGAST") == 0)
719 #if CV_MAJOR_VERSION < 3 720 UWARN(
"Find-Object is not built with OpenCV 3 so AGAST cannot be used!");
722 feature2D =
new Feature2D(cv::AgastFeatureDetector::create(
723 getFeature2D_AGAST_threshold(),
724 getFeature2D_AGAST_nonmaxSuppression()));
726 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
728 else if(strategies.at(index).compare(
"GFTT") == 0)
730 #if CV_MAJOR_VERSION < 3 731 feature2D =
new Feature2D(cv::Ptr<cv::FeatureDetector>(
new cv::GFTTDetector(
732 getFeature2D_GFTT_maxCorners(),
733 getFeature2D_GFTT_qualityLevel(),
734 getFeature2D_GFTT_minDistance(),
735 getFeature2D_GFTT_blockSize(),
736 getFeature2D_GFTT_useHarrisDetector(),
737 getFeature2D_GFTT_k())));
739 feature2D =
new Feature2D(cv::GFTTDetector::create(
740 getFeature2D_GFTT_maxCorners(),
741 getFeature2D_GFTT_qualityLevel(),
742 getFeature2D_GFTT_minDistance(),
743 getFeature2D_GFTT_blockSize(),
744 getFeature2D_GFTT_useHarrisDetector(),
745 getFeature2D_GFTT_k()));
747 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
749 else if(strategies.at(index).compare(
"MSER") == 0)
751 #if CV_MAJOR_VERSION < 3 752 feature2D =
new Feature2D(cv::Ptr<cv::FeatureDetector>(
new cv::MSER(
753 getFeature2D_MSER_delta(),
754 getFeature2D_MSER_minArea(),
755 getFeature2D_MSER_maxArea(),
756 getFeature2D_MSER_maxVariation(),
757 getFeature2D_MSER_minDiversity(),
758 getFeature2D_MSER_maxEvolution(),
759 getFeature2D_MSER_areaThreshold(),
760 getFeature2D_MSER_minMargin(),
761 getFeature2D_MSER_edgeBlurSize())));
763 feature2D =
new Feature2D(cv::MSER::create(
764 getFeature2D_MSER_delta(),
765 getFeature2D_MSER_minArea(),
766 getFeature2D_MSER_maxArea(),
767 getFeature2D_MSER_maxVariation(),
768 getFeature2D_MSER_minDiversity(),
769 getFeature2D_MSER_maxEvolution(),
770 getFeature2D_MSER_areaThreshold(),
771 getFeature2D_MSER_minMargin(),
772 getFeature2D_MSER_edgeBlurSize()));
774 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
776 else if(strategies.at(index).compare(
"ORB") == 0)
778 if(getFeature2D_ORB_gpu() && CVCUDA::getCudaEnabledDeviceCount())
781 getFeature2D_ORB_nFeatures(),
782 getFeature2D_ORB_scaleFactor(),
783 getFeature2D_ORB_nLevels(),
784 getFeature2D_ORB_edgeThreshold(),
785 getFeature2D_ORB_firstLevel(),
786 getFeature2D_ORB_WTA_K(),
787 getFeature2D_ORB_scoreType(),
788 getFeature2D_ORB_patchSize(),
789 getFeature2D_Fast_threshold(),
790 #
if CV_MAJOR_VERSION < 3
791 getFeature2D_Fast_nonmaxSuppression());
793 getFeature2D_ORB_blurForDescriptor());
795 UDEBUG(
"type=%s (GPU)", strategies.at(index).toStdString().c_str());
799 #if CV_MAJOR_VERSION < 3 800 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::ORB(
801 getFeature2D_ORB_nFeatures(),
802 getFeature2D_ORB_scaleFactor(),
803 getFeature2D_ORB_nLevels(),
804 getFeature2D_ORB_edgeThreshold(),
805 getFeature2D_ORB_firstLevel(),
806 getFeature2D_ORB_WTA_K(),
807 getFeature2D_ORB_scoreType(),
808 getFeature2D_ORB_patchSize())));
810 feature2D =
new Feature2D(cv::ORB::create(
811 getFeature2D_ORB_nFeatures(),
812 getFeature2D_ORB_scaleFactor(),
813 getFeature2D_ORB_nLevels(),
814 getFeature2D_ORB_edgeThreshold(),
815 getFeature2D_ORB_firstLevel(),
816 getFeature2D_ORB_WTA_K(),
817 getFeature2D_ORB_scoreType(),
818 getFeature2D_ORB_patchSize(),
819 getFeature2D_Fast_threshold()));
821 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
824 else if(strategies.at(index).compare(
"Star") == 0)
826 #if CV_MAJOR_VERSION < 3 827 feature2D =
new Feature2D(cv::Ptr<cv::FeatureDetector>(
new cv::StarFeatureDetector(
828 getFeature2D_Star_maxSize(),
829 getFeature2D_Star_responseThreshold(),
830 getFeature2D_Star_lineThresholdProjected(),
831 getFeature2D_Star_lineThresholdBinarized(),
832 getFeature2D_Star_suppressNonmaxSize())));
834 #ifdef HAVE_OPENCV_XFEATURES2D 835 feature2D =
new Feature2D(cv::xfeatures2d::StarDetector::create(
836 getFeature2D_Star_maxSize(),
837 getFeature2D_Star_responseThreshold(),
838 getFeature2D_Star_lineThresholdProjected(),
839 getFeature2D_Star_lineThresholdBinarized(),
840 getFeature2D_Star_suppressNonmaxSize()));
842 UWARN(
"Find-Object is not built with OpenCV xfeatures2d module so Star cannot be used!");
845 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
847 else if(strategies.at(index).compare(
"BRISK") == 0)
849 #if CV_MAJOR_VERSION < 3 850 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::BRISK(
851 getFeature2D_BRISK_thresh(),
852 getFeature2D_BRISK_octaves(),
853 getFeature2D_BRISK_patternScale())));
855 feature2D =
new Feature2D(cv::BRISK::create(
856 getFeature2D_BRISK_thresh(),
857 getFeature2D_BRISK_octaves(),
858 getFeature2D_BRISK_patternScale()));
860 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
862 else if(strategies.at(index).compare(
"KAZE") == 0)
864 #if CV_MAJOR_VERSION < 3 865 UWARN(
"Find-Object is not built with OpenCV 3 so KAZE cannot be used!");
867 feature2D =
new Feature2D(cv::KAZE::create(
868 getFeature2D_KAZE_extended(),
869 getFeature2D_KAZE_upright(),
870 getFeature2D_KAZE_threshold(),
871 getFeature2D_KAZE_nOctaves(),
872 getFeature2D_KAZE_nOctaveLayers(),
873 cv::KAZE::DIFF_PM_G2));
875 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
877 else if(strategies.at(index).compare(
"AKAZE") == 0)
879 #if CV_MAJOR_VERSION < 3 880 UWARN(
"Find-Object is not built with OpenCV 3 so AKAZE cannot be used!");
882 feature2D =
new Feature2D(cv::AKAZE::create(
883 cv::AKAZE::DESCRIPTOR_MLDB,
884 getFeature2D_AKAZE_descriptorSize(),
885 getFeature2D_AKAZE_descriptorChannels(),
886 getFeature2D_AKAZE_threshold(),
887 getFeature2D_AKAZE_nOctaves(),
888 getFeature2D_AKAZE_nOctaveLayers(),
889 cv::KAZE::DIFF_PM_G2));
891 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
893 #if FINDOBJECT_NONFREE == 1 894 else if(strategies.at(index).compare(
"SIFT") == 0)
896 #if CV_MAJOR_VERSION < 3 897 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::SIFT(
898 getFeature2D_SIFT_nfeatures(),
899 getFeature2D_SIFT_nOctaveLayers(),
900 getFeature2D_SIFT_contrastThreshold(),
901 getFeature2D_SIFT_edgeThreshold(),
902 getFeature2D_SIFT_sigma())));
904 feature2D =
new Feature2D(cv::xfeatures2d::SIFT::create(
905 getFeature2D_SIFT_nfeatures(),
906 getFeature2D_SIFT_nOctaveLayers(),
907 getFeature2D_SIFT_contrastThreshold(),
908 getFeature2D_SIFT_edgeThreshold(),
909 getFeature2D_SIFT_sigma()));
911 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
913 else if(strategies.at(index).compare(
"SURF") == 0)
915 if(getFeature2D_SURF_gpu() && CVCUDA::getCudaEnabledDeviceCount())
917 feature2D =
new GPUSURF(
918 getFeature2D_SURF_hessianThreshold(),
919 getFeature2D_SURF_nOctaves(),
920 getFeature2D_SURF_nOctaveLayers(),
921 getFeature2D_SURF_extended(),
922 getFeature2D_SURF_keypointsRatio(),
923 getFeature2D_SURF_upright());
924 UDEBUG(
"type=%s (GPU)", strategies.at(index).toStdString().c_str());
928 #if CV_MAJOR_VERSION < 3 929 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::SURF(
930 getFeature2D_SURF_hessianThreshold(),
931 getFeature2D_SURF_nOctaves(),
932 getFeature2D_SURF_nOctaveLayers(),
933 getFeature2D_SURF_extended(),
934 getFeature2D_SURF_upright())));
936 feature2D =
new Feature2D(cv::xfeatures2d::SURF::create(
937 getFeature2D_SURF_hessianThreshold(),
938 getFeature2D_SURF_nOctaves(),
939 getFeature2D_SURF_nOctaveLayers(),
940 getFeature2D_SURF_extended(),
941 getFeature2D_SURF_upright()));
943 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
957 QString str = getFeature2D_2Descriptor();
958 QStringList split = str.split(
':');
962 int index = split.first().toInt(&ok);
965 QStringList strategies = split.last().split(
';');
966 if(index>=0 && index<strategies.size())
969 #if FINDOBJECT_NONFREE == 0 971 if(strategies.at(index).compare(
"SIFT") == 0 ||
972 strategies.at(index).compare(
"SURF") == 0)
974 index = Settings::defaultFeature2D_2Descriptor().split(
':').first().toInt();
975 UERROR(
"Find-Object is not built with OpenCV nonfree module so " 976 "SIFT/SURF cannot be used! Using default \"%s\" instead.",
977 strategies.at(index).toStdString().c_str());
982 #if CV_MAJOR_VERSION < 3 983 if(strategies.at(index).compare(
"KAZE") == 0 ||
984 strategies.at(index).compare(
"AKAZE") == 0)
986 index = Settings::defaultFeature2D_2Descriptor().split(
':').first().toInt();
987 UERROR(
"Find-Object is built with OpenCV 2 so " 988 "KAZE/AKAZE cannot be used! Using default \"%s\" instead.",
989 strategies.at(index).toStdString().c_str());
993 #ifndef HAVE_OPENCV_XFEATURES2D 994 if(strategies.at(index).compare(
"Brief") == 0 ||
995 strategies.at(index).compare(
"FREAK") == 0 ||
996 strategies.at(index).compare(
"LUCID") == 0 ||
997 strategies.at(index).compare(
"LATCH") == 0 ||
998 strategies.at(index).compare(
"DAISY") == 0)
1000 index = Settings::defaultFeature2D_2Descriptor().split(
':').first().toInt();
1001 UERROR(
"Find-Object is not built with OpenCV xfeatures2d module so " 1002 "Brief/FREAK/LUCID/LATCH/DAISY cannot be used! Using default \"%s\" instead.",
1003 strategies.at(index).toStdString().c_str());
1009 if(strategies.at(index).compare(
"Brief") == 0)
1011 #if CV_MAJOR_VERSION < 3 1012 feature2D =
new Feature2D(cv::Ptr<cv::DescriptorExtractor>(
new cv::BriefDescriptorExtractor(
1013 getFeature2D_Brief_bytes())));
1015 #ifdef HAVE_OPENCV_XFEATURES2D 1016 feature2D =
new Feature2D(cv::xfeatures2d::BriefDescriptorExtractor::create(
1017 getFeature2D_Brief_bytes()));
1019 UWARN(
"Find-Object is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1022 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1024 else if(strategies.at(index).compare(
"ORB") == 0)
1026 if(getFeature2D_ORB_gpu() && CVCUDA::getCudaEnabledDeviceCount())
1029 getFeature2D_ORB_nFeatures(),
1030 getFeature2D_ORB_scaleFactor(),
1031 getFeature2D_ORB_nLevels(),
1032 getFeature2D_ORB_edgeThreshold(),
1033 getFeature2D_ORB_firstLevel(),
1034 getFeature2D_ORB_WTA_K(),
1035 getFeature2D_ORB_scoreType(),
1036 getFeature2D_ORB_patchSize(),
1037 getFeature2D_Fast_threshold(),
1038 getFeature2D_Fast_nonmaxSuppression());
1039 UDEBUG(
"type=%s (GPU)", strategies.at(index).toStdString().c_str());
1043 #if CV_MAJOR_VERSION < 3 1044 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::ORB(
1045 getFeature2D_ORB_nFeatures(),
1046 getFeature2D_ORB_scaleFactor(),
1047 getFeature2D_ORB_nLevels(),
1048 getFeature2D_ORB_edgeThreshold(),
1049 getFeature2D_ORB_firstLevel(),
1050 getFeature2D_ORB_WTA_K(),
1051 getFeature2D_ORB_scoreType(),
1052 getFeature2D_ORB_patchSize())));
1054 feature2D =
new Feature2D(cv::ORB::create(
1055 getFeature2D_ORB_nFeatures(),
1056 getFeature2D_ORB_scaleFactor(),
1057 getFeature2D_ORB_nLevels(),
1058 getFeature2D_ORB_edgeThreshold(),
1059 getFeature2D_ORB_firstLevel(),
1060 getFeature2D_ORB_WTA_K(),
1061 getFeature2D_ORB_scoreType(),
1062 getFeature2D_ORB_patchSize(),
1063 getFeature2D_Fast_threshold()));
1065 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1068 else if(strategies.at(index).compare(
"BRISK") == 0)
1070 #if CV_MAJOR_VERSION < 3 1071 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::BRISK(
1072 getFeature2D_BRISK_thresh(),
1073 getFeature2D_BRISK_octaves(),
1074 getFeature2D_BRISK_patternScale())));
1076 feature2D =
new Feature2D(cv::BRISK::create(
1077 getFeature2D_BRISK_thresh(),
1078 getFeature2D_BRISK_octaves(),
1079 getFeature2D_BRISK_patternScale()));
1081 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1083 else if(strategies.at(index).compare(
"KAZE") == 0)
1085 #if CV_MAJOR_VERSION < 3 1086 UWARN(
"Find-Object is not built with OpenCV 3 so KAZE cannot be used!");
1088 feature2D =
new Feature2D(cv::KAZE::create(
1089 getFeature2D_KAZE_extended(),
1090 getFeature2D_KAZE_upright(),
1091 getFeature2D_KAZE_threshold(),
1092 getFeature2D_KAZE_nOctaves(),
1093 getFeature2D_KAZE_nOctaveLayers(),
1094 cv::KAZE::DIFF_PM_G2));
1096 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1098 else if(strategies.at(index).compare(
"AKAZE") == 0)
1100 #if CV_MAJOR_VERSION < 3 1101 UWARN(
"Find-Object is not built with OpenCV 3 so AKAZE cannot be used!");
1103 feature2D =
new Feature2D(cv::AKAZE::create(
1104 cv::AKAZE::DESCRIPTOR_MLDB,
1105 getFeature2D_AKAZE_descriptorSize(),
1106 getFeature2D_AKAZE_descriptorChannels(),
1107 getFeature2D_AKAZE_threshold(),
1108 getFeature2D_AKAZE_nOctaves(),
1109 getFeature2D_AKAZE_nOctaveLayers(),
1110 cv::KAZE::DIFF_PM_G2));
1112 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1114 else if(strategies.at(index).compare(
"FREAK") == 0)
1116 #if CV_MAJOR_VERSION < 3 1117 feature2D =
new Feature2D(cv::Ptr<cv::DescriptorExtractor>(
new cv::FREAK(
1118 getFeature2D_FREAK_orientationNormalized(),
1119 getFeature2D_FREAK_scaleNormalized(),
1120 getFeature2D_FREAK_patternScale(),
1121 getFeature2D_FREAK_nOctaves())));
1123 #ifdef HAVE_OPENCV_XFEATURES2D 1124 feature2D =
new Feature2D(cv::xfeatures2d::FREAK::create(
1125 getFeature2D_FREAK_orientationNormalized(),
1126 getFeature2D_FREAK_scaleNormalized(),
1127 getFeature2D_FREAK_patternScale(),
1128 getFeature2D_FREAK_nOctaves()));
1130 UWARN(
"Find-Object is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1134 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1136 #ifdef HAVE_OPENCV_XFEATURES2D 1137 else if(strategies.at(index).compare(
"LUCID") == 0)
1139 feature2D =
new Feature2D(cv::xfeatures2d::LUCID::create(
1140 getFeature2D_LUCID_kernel(),
1141 getFeature2D_LUCID_blur_kernel()));
1143 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1145 else if(strategies.at(index).compare(
"LATCH") == 0)
1147 feature2D =
new Feature2D(cv::xfeatures2d::LATCH::create(
1148 getFeature2D_LATCH_bytes(),
1149 getFeature2D_LATCH_rotationInvariance(),
1150 getFeature2D_LATCH_half_ssd_size()));
1152 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1154 else if(strategies.at(index).compare(
"DAISY") == 0)
1156 feature2D =
new Feature2D(cv::xfeatures2d::DAISY::create(
1157 getFeature2D_DAISY_radius(),
1158 getFeature2D_DAISY_q_radius(),
1159 getFeature2D_DAISY_q_theta(),
1160 getFeature2D_DAISY_q_hist(),
1161 cv::xfeatures2d::DAISY::NRM_NONE,
1163 getFeature2D_DAISY_interpolation(),
1164 getFeature2D_DAISY_use_orientation()));
1166 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1169 #if FINDOBJECT_NONFREE == 1 1170 else if(strategies.at(index).compare(
"SIFT") == 0)
1172 #if CV_MAJOR_VERSION < 3 1173 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::SIFT(
1174 getFeature2D_SIFT_nfeatures(),
1175 getFeature2D_SIFT_nOctaveLayers(),
1176 getFeature2D_SIFT_contrastThreshold(),
1177 getFeature2D_SIFT_edgeThreshold(),
1178 getFeature2D_SIFT_sigma())));
1180 feature2D =
new Feature2D(cv::xfeatures2d::SIFT::create(
1181 getFeature2D_SIFT_nfeatures(),
1182 getFeature2D_SIFT_nOctaveLayers(),
1183 getFeature2D_SIFT_contrastThreshold(),
1184 getFeature2D_SIFT_edgeThreshold(),
1185 getFeature2D_SIFT_sigma()));
1187 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1189 else if(strategies.at(index).compare(
"SURF") == 0)
1191 if(getFeature2D_SURF_gpu() && CVCUDA::getCudaEnabledDeviceCount())
1193 feature2D =
new GPUSURF(
1194 getFeature2D_SURF_hessianThreshold(),
1195 getFeature2D_SURF_nOctaves(),
1196 getFeature2D_SURF_nOctaveLayers(),
1197 getFeature2D_SURF_extended(),
1198 getFeature2D_SURF_keypointsRatio(),
1199 getFeature2D_SURF_upright());
1200 UDEBUG(
"type=%s (GPU)", strategies.at(index).toStdString().c_str());
1204 #if CV_MAJOR_VERSION < 3 1205 feature2D =
new Feature2D(cv::Ptr<cv::Feature2D>(
new cv::SURF(
1206 getFeature2D_SURF_hessianThreshold(),
1207 getFeature2D_SURF_nOctaves(),
1208 getFeature2D_SURF_nOctaveLayers(),
1209 getFeature2D_SURF_extended(),
1210 getFeature2D_SURF_upright())));
1212 feature2D =
new Feature2D(cv::xfeatures2d::SURF::create(
1213 getFeature2D_SURF_hessianThreshold(),
1214 getFeature2D_SURF_nOctaves(),
1215 getFeature2D_SURF_nOctaveLayers(),
1216 getFeature2D_SURF_extended(),
1217 getFeature2D_SURF_upright()));
1219 UDEBUG(
"type=%s", strategies.at(index).toStdString().c_str());
1232 int index = getFeature2D_1Detector().split(
':').first().toInt();
1233 return getFeature2D_1Detector().split(
':').last().split(
';').at(index);
1238 int index = getFeature2D_2Descriptor().split(
':').first().toInt();
1239 return getFeature2D_2Descriptor().split(
':').last().split(
';').at(index);
1244 int index = getNearestNeighbor_1Strategy().split(
':').first().toInt();
1245 return getNearestNeighbor_1Strategy().split(
':').last().split(
';').at(index);
1250 bool bruteForce =
false;
1251 QString str = getNearestNeighbor_1Strategy();
1252 QStringList split = str.split(
':');
1256 int index = split.first().toInt(&ok);
1259 QStringList strategies = split.last().split(
';');
1260 if(strategies.size() >= 7 && index == 6)
1271 cv::flann::IndexParams * params = 0;
1272 QString str = getNearestNeighbor_1Strategy();
1273 QStringList split = str.split(
':');
1277 int index = split.first().toInt(&ok);
1280 QStringList strategies = split.last().split(
';');
1281 if(strategies.size() >= 6 && index>=0 && index<6)
1286 if(strategies.at(index).compare(
"Linear") == 0)
1288 UDEBUG(
"type=%s",
"Linear");
1289 params =
new cv::flann::LinearIndexParams();
1293 if(strategies.at(index).compare(
"KDTree") == 0)
1295 UDEBUG(
"type=%s",
"KDTree");
1296 params =
new cv::flann::KDTreeIndexParams(
1297 getNearestNeighbor_KDTree_trees());
1301 if(strategies.at(index).compare(
"KMeans") == 0)
1303 cvflann::flann_centers_init_t centers_init = cvflann::FLANN_CENTERS_RANDOM;
1304 QString str = getNearestNeighbor_KMeans_centers_init();
1305 QStringList split = str.split(
':');
1309 int index = split.first().toInt(&ok);
1312 centers_init = (cvflann::flann_centers_init_t)index;
1315 UDEBUG(
"type=%s",
"KMeans");
1316 params =
new cv::flann::KMeansIndexParams(
1317 getNearestNeighbor_KMeans_branching(),
1318 getNearestNeighbor_KMeans_iterations(),
1320 getNearestNeighbor_KMeans_cb_index());
1324 if(strategies.at(index).compare(
"Composite") == 0)
1326 cvflann::flann_centers_init_t centers_init = cvflann::FLANN_CENTERS_RANDOM;
1327 QString str = getNearestNeighbor_Composite_centers_init();
1328 QStringList split = str.split(
':');
1332 int index = split.first().toInt(&ok);
1335 centers_init = (cvflann::flann_centers_init_t)index;
1338 UDEBUG(
"type=%s",
"Composite");
1339 params =
new cv::flann::CompositeIndexParams(
1340 getNearestNeighbor_Composite_trees(),
1341 getNearestNeighbor_Composite_branching(),
1342 getNearestNeighbor_Composite_iterations(),
1344 getNearestNeighbor_Composite_cb_index());
1348 if(strategies.at(index).compare(
"Autotuned") == 0)
1350 UDEBUG(
"type=%s",
"Autotuned");
1351 params =
new cv::flann::AutotunedIndexParams(
1352 getNearestNeighbor_Autotuned_target_precision(),
1353 getNearestNeighbor_Autotuned_build_weight(),
1354 getNearestNeighbor_Autotuned_memory_weight(),
1355 getNearestNeighbor_Autotuned_sample_fraction());
1359 if(strategies.at(index).compare(
"Lsh") == 0)
1361 UDEBUG(
"type=%s",
"Lsh");
1362 params =
new cv::flann::LshIndexParams(
1363 getNearestNeighbor_Lsh_table_number(),
1364 getNearestNeighbor_Lsh_key_size(),
1365 getNearestNeighbor_Lsh_multi_probe_level());
1377 UERROR(
"NN strategy not found !? Using default KDTRee...");
1378 params =
new cv::flann::KDTreeIndexParams();
1385 cvflann::flann_distance_t
distance = cvflann::FLANN_DIST_L2;
1386 QString str = getNearestNeighbor_2Distance_type();
1387 QStringList split = str.split(
':');
1391 int index = split.first().toInt(&ok);
1394 QStringList strategies = split.last().split(
';');
1395 if(strategies.size() == 9 && index>=0 && index<=8)
1397 distance = (cvflann::flann_distance_t)(index+1);
1406 int method = cv::RANSAC;
1407 QString str = getHomography_method();
1408 QStringList split = str.split(
':');
1412 int index = split.first().toInt(&ok);
1415 QStringList strategies = split.last().split(
';');
1416 if(strategies.size() == 2 && index>=0 && index<2)
1420 #if CV_MAJOR_VERSION >= 3 1429 method = cv::RANSAC;
1435 UDEBUG(
"method=%d", method);
1439 #if CV_MAJOR_VERSION < 3 1441 featureDetector_(featureDetector)
1458 std::vector<cv::KeyPoint> & keypoints,
1459 const cv::Mat & mask)
1461 #if CV_MAJOR_VERSION < 3 1474 UERROR(
"Feature2D not set!?!?");
1479 std::vector<cv::KeyPoint> & keypoints,
1480 cv::Mat & descriptors)
1482 #if CV_MAJOR_VERSION < 3 1491 feature2D_->compute(image, keypoints, descriptors);
1495 UERROR(
"Feature2D not set!?!?");
1500 std::vector<cv::KeyPoint> & keypoints,
1501 cv::Mat & descriptors,
1502 const cv::Mat & mask)
1506 #if CV_MAJOR_VERSION < 3 1507 (*feature2D_)(image, mask, keypoints, descriptors);
1509 feature2D_->detectAndCompute(image, mask, keypoints, descriptors);
1514 UERROR(
"Cannot use Feature2D::detectAndCompute() if feature2D member is not set.");
static QString iniDefaultPath()
static cv::flann::IndexParams * createFlannIndexParams()
static int getHomographyMethod()
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())
static Feature2D * createKeypointDetector()
static QVariant getParameter(const QString &key)
virtual void detectAndCompute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &mask=cv::Mat())
static const ParametersType & getParametersType()
cv::Ptr< cv::FeatureDetector > featureDetector_
static ParametersType parametersType_
GPUFAST(int threshold=Settings::defaultFeature2D_Fast_threshold(), bool nonmaxSuppression=Settings::defaultFeature2D_Fast_nonmaxSuppression(), double keypointsRatio=Settings::defaultFeature2D_Fast_keypointsRatio())
static cvflann::flann_distance_t getFlannDistanceType()
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
static void loadWindowSettings(QByteArray &windowGeometry, QByteArray &windowState, const QString &fileName=QString())
#define UASSERT(condition)
static QString currentDetectorType()
static DescriptionsMap descriptions_
static void loadSettings(const QString &fileName=QString())
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
QMap< QString, QString > ParametersType
static void setParameter(const QString &key, const QVariant &value)
static void init(const QString &fileName)
QMap< QString, QVariant > ParametersMap
static QString currentDescriptorType()
static ParametersMap parameters_
static Settings dummyInit_
virtual void detectAndCompute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &mask=cv::Mat())
QMap< QString, QString > DescriptionsMap
static void saveWindowSettings(const QByteArray &windowGeometry, const QByteArray &windowState, const QString &fileName=QString())
static QString workingDirectory()
static QString currentNearestNeighborType()
static bool isBruteForceNearestNeighbor()
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
static QString iniDefaultFileName()
ULogger class and convenient macros.
static Feature2D * createDescriptorExtractor()
static ParametersMap defaultParameters_
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
cv::Ptr< cv::DescriptorExtractor > descriptorExtractor_
cv::Ptr< cv::Feature2D > feature2D_
virtual void detectAndCompute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &mask=cv::Mat())
static void saveSettings(const QString &fileName=QString())