00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #include "find_object/Camera.h"
00029 #include "find_object/Settings.h"
00030 #include "find_object/utilite/ULogger.h"
00031
00032 #include <QtCore/QSettings>
00033 #include <QtCore/QStringList>
00034 #include <QtCore/QDir>
00035 #include <stdio.h>
00036 #include <opencv2/calib3d/calib3d.hpp>
00037 #if FINDOBJECT_NONFREE == 1
00038 #include <opencv2/nonfree/features2d.hpp>
00039 #include <opencv2/nonfree/gpu.hpp>
00040 #endif
00041 #include <opencv2/gpu/gpu.hpp>
00042
00043 namespace find_object {
00044
00045 ParametersMap Settings::defaultParameters_;
00046 ParametersMap Settings::parameters_;
00047 ParametersType Settings::parametersType_;
00048 DescriptionsMap Settings::descriptions_;
00049 Settings Settings::dummyInit_;
00050 QString Settings::iniPath_;
00051
00052 QString Settings::workingDirectory()
00053 {
00054 #ifdef WIN32
00055 return QString("%1/Documents/%2").arg(QDir::homePath()).arg(PROJECT_NAME);
00056 #else
00057 return QString("%1").arg(QDir::homePath());
00058 #endif
00059 }
00060
00061 QString Settings::iniDefaultPath()
00062 {
00063 #ifdef WIN32
00064 return QString("%1/Documents/%2/%3").arg(QDir::homePath()).arg(PROJECT_NAME).arg(Settings::iniDefaultFileName());
00065 #else
00066 return QString("%1/.%2/%3").arg(QDir::homePath()).arg(PROJECT_PREFIX).arg(Settings::iniDefaultFileName());
00067 #endif
00068 }
00069
00070 QString Settings::iniPath()
00071 {
00072 if(!iniPath_.isNull())
00073 {
00074 return iniPath_;
00075 }
00076 return iniDefaultPath();
00077 }
00078
00079 void Settings::init(const QString & fileName)
00080 {
00081 iniPath_ = fileName;
00082 loadSettings(iniPath_);
00083 }
00084
00085 void Settings::loadSettings(const QString & fileName)
00086 {
00087 QString path = fileName;
00088 if(fileName.isEmpty())
00089 {
00090 path = iniPath();
00091 }
00092 if(!path.isEmpty())
00093 {
00094 QSettings ini(path, QSettings::IniFormat);
00095 for(ParametersMap::const_iterator iter = defaultParameters_.begin(); iter!=defaultParameters_.end(); ++iter)
00096 {
00097 const QString & key = iter.key();
00098 QVariant value = ini.value(key, QVariant());
00099 if(value.isValid())
00100 {
00101 QString str = value.toString();
00102 if(str.contains(";"))
00103 {
00104 if(str.size() != getParameter(key).toString().size())
00105 {
00106
00107
00108 QChar index = str.at(0);
00109 str = getParameter(key).toString();
00110 str[0] = index.toAscii();
00111 value = QVariant(str);
00112 UINFO("Updated list of parameter \"%s\"", key.toStdString().c_str());
00113 }
00114 #if FINDOBJECT_NONFREE == 0
00115 QChar index = str.at(0);
00116 if(key.compare(Settings::kFeature2D_1Detector()) == 0)
00117 {
00118 if(index == '5' || index == '7')
00119 {
00120 index = Settings::defaultFeature2D_1Detector().at(0);
00121 int indexInt = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
00122 UWARN("Trying to set \"%s\" to SIFT/SURF but Find-Object isn't built "
00123 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
00124 Settings::kFeature2D_1Detector().toStdString().c_str(),
00125 Settings::defaultFeature2D_1Detector().split(':').last().split(";").at(indexInt).toStdString().c_str());
00126 }
00127 }
00128 else if(key.compare(Settings::kFeature2D_2Descriptor()) == 0)
00129 {
00130 if(index == '2' || index == '3')
00131 {
00132 index = Settings::defaultFeature2D_2Descriptor().at(0);
00133 int indexInt = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
00134 UWARN("Trying to set \"%s\" to SIFT/SURF but Find-Object isn't built "
00135 "with the nonfree module from OpenCV. Keeping default combo value: %s.",
00136 Settings::kFeature2D_2Descriptor().toStdString().c_str(),
00137 Settings::defaultFeature2D_2Descriptor().split(':').last().split(";").at(indexInt).toStdString().c_str());
00138 }
00139 }
00140 else if(key.compare(Settings::kNearestNeighbor_1Strategy()) == 0)
00141 {
00142 if(index <= '4')
00143 {
00144 index = Settings::defaultNearestNeighbor_1Strategy().at(0);
00145 int indexInt = Settings::defaultNearestNeighbor_1Strategy().split(':').first().toInt();
00146 UWARN("Trying to set \"%s\" to one FLANN approach but Find-Object isn't built "
00147 "with the nonfree module from OpenCV and FLANN cannot be used "
00148 "with binary descriptors. Keeping default combo value: %s.",
00149 Settings::kNearestNeighbor_1Strategy().toStdString().c_str(),
00150 Settings::defaultNearestNeighbor_1Strategy().split(':').last().split(";").at(indexInt).toStdString().c_str());
00151 }
00152 }
00153 str = getParameter(key).toString();
00154 str[0] = index.toAscii();
00155 value = QVariant(str);
00156 #endif
00157 }
00158 setParameter(key, value);
00159 }
00160 }
00161 UINFO("Settings loaded from %s.", path.toStdString().c_str());
00162 }
00163 else
00164 {
00165 parameters_ = defaultParameters_;
00166 UINFO("Settings set to defaults.");
00167 }
00168
00169 if(cv::gpu::getCudaEnabledDeviceCount() == 0)
00170 {
00171 #if FINDOBJECT_NONFREE == 1
00172 Settings::setFeature2D_SURF_gpu(false);
00173 #endif
00174 Settings::setFeature2D_Fast_gpu(false);
00175 Settings::setFeature2D_ORB_gpu(false);
00176 Settings::setNearestNeighbor_BruteForce_gpu(false);
00177 }
00178 }
00179
00180 void Settings::loadWindowSettings(QByteArray & windowGeometry, QByteArray & windowState, const QString & fileName)
00181 {
00182 QString path = fileName;
00183 if(fileName.isEmpty())
00184 {
00185 path = iniPath();
00186 }
00187
00188 if(!path.isEmpty())
00189 {
00190 QSettings ini(path, QSettings::IniFormat);
00191
00192 QVariant value = ini.value("windowGeometry", QVariant());
00193 if(value.isValid())
00194 {
00195 windowGeometry = value.toByteArray();
00196 }
00197
00198 value = ini.value("windowState", QVariant());
00199 if(value.isValid())
00200 {
00201 windowState = value.toByteArray();
00202 }
00203
00204 UINFO("Window settings loaded from %s", path.toStdString().c_str());
00205 }
00206 }
00207
00208 void Settings::saveSettings(const QString & fileName)
00209 {
00210 QString path = fileName;
00211 if(fileName.isEmpty())
00212 {
00213 path = iniPath();
00214 }
00215 if(!path.isEmpty())
00216 {
00217 QSettings ini(path, QSettings::IniFormat);
00218 for(ParametersMap::const_iterator iter = parameters_.begin(); iter!=parameters_.end(); ++iter)
00219 {
00220 QString type = Settings::getParametersType().value(iter.key());
00221 if(type.compare("float") == 0)
00222 {
00223 ini.setValue(iter.key(), QString::number(iter.value().toFloat(),'g',6));
00224 }
00225 else
00226 {
00227 ini.setValue(iter.key(), iter.value());
00228 }
00229 }
00230 UINFO("Settings saved to %s", path.toStdString().c_str());
00231 }
00232 }
00233
00234 void Settings::saveWindowSettings(const QByteArray & windowGeometry, const QByteArray & windowState, const QString & fileName)
00235 {
00236 QString path = fileName;
00237 if(fileName.isEmpty())
00238 {
00239 path = iniPath();
00240 }
00241 if(!path.isEmpty())
00242 {
00243 QSettings ini(path, QSettings::IniFormat);
00244 if(!windowGeometry.isEmpty())
00245 {
00246 ini.setValue("windowGeometry", windowGeometry);
00247 }
00248 if(!windowState.isEmpty())
00249 {
00250 ini.setValue("windowState", windowState);
00251 }
00252 UINFO("Window settings saved to %s", path.toStdString().c_str());
00253 }
00254 }
00255
00256 class GPUFeature2D
00257 {
00258 public:
00259 GPUFeature2D() {}
00260 virtual ~GPUFeature2D() {}
00261
00262 virtual void detectKeypoints(const cv::Mat & image,
00263 std::vector<cv::KeyPoint> & keypoints,
00264 const cv::Mat & mask = cv::Mat()) = 0;
00265
00266 virtual void computeDescriptors(const cv::Mat & image,
00267 std::vector<cv::KeyPoint> & keypoints,
00268 cv::Mat & descriptors) = 0;
00269 };
00270
00271 #if FINDOBJECT_NONFREE == 1
00272 class GPUSURF : public GPUFeature2D
00273 {
00274 public:
00275 GPUSURF(double hessianThreshold,
00276 int nOctaves,
00277 int nOctaveLayers,
00278 bool extended,
00279 float keypointsRatio,
00280 bool upright) :
00281 surf_(hessianThreshold,
00282 nOctaves,
00283 nOctaveLayers,
00284 extended,
00285 keypointsRatio,
00286 upright)
00287 {
00288 }
00289 virtual ~GPUSURF() {}
00290
00291 void detectKeypoints(const cv::Mat & image,
00292 std::vector<cv::KeyPoint> & keypoints,
00293 const cv::Mat & mask = cv::Mat())
00294 {
00295 cv::gpu::GpuMat imgGpu(image);
00296 cv::gpu::GpuMat maskGpu(mask);
00297 try
00298 {
00299 surf_(imgGpu, maskGpu, keypoints);
00300 }
00301 catch(cv::Exception &e)
00302 {
00303 UERROR("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF "
00304 "is too high for the size of the image (%d,%d).)",
00305 e.msg.c_str(),
00306 surf_.nOctaves,
00307 image.cols,
00308 image.rows);
00309 }
00310 }
00311
00312 void computeDescriptors( const cv::Mat& image,
00313 std::vector<cv::KeyPoint>& keypoints,
00314 cv::Mat& descriptors)
00315 {
00316 std::vector<float> d;
00317 cv::gpu::GpuMat imgGpu(image);
00318 cv::gpu::GpuMat descriptorsGPU;
00319 try
00320 {
00321 surf_(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU, true);
00322 }
00323 catch(cv::Exception &e)
00324 {
00325 UERROR("GPUSURF error: %s \n(If something about layer_rows, parameter nOctaves=%d of SURF "
00326 "is too high for the size of the image (%d,%d).)",
00327 e.msg.c_str(),
00328 surf_.nOctaves,
00329 image.cols,
00330 image.rows);
00331 }
00332
00333
00334 if (descriptorsGPU.empty())
00335 descriptors = cv::Mat();
00336 else
00337 {
00338 UASSERT(descriptorsGPU.type() == CV_32F);
00339 descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
00340 descriptorsGPU.download(descriptors);
00341 }
00342 }
00343 private:
00344 cv::gpu::SURF_GPU surf_;
00345 };
00346 #endif
00347
00348 class GPUFAST : public GPUFeature2D
00349 {
00350 public:
00351 GPUFAST(int threshold=Settings::defaultFeature2D_Fast_threshold(),
00352 bool nonmaxSuppression=Settings::defaultFeature2D_Fast_nonmaxSuppression(),
00353 double keypointsRatio=Settings::defaultFeature2D_Fast_keypointsRatio()) :
00354 fast_(threshold,
00355 nonmaxSuppression,
00356 keypointsRatio)
00357 {
00358 }
00359 virtual ~GPUFAST() {}
00360
00361 protected:
00362 void detectKeypoints(const cv::Mat & image,
00363 std::vector<cv::KeyPoint> & keypoints,
00364 const cv::Mat & mask = cv::Mat())
00365 {
00366 cv::gpu::GpuMat imgGpu(image);
00367 cv::gpu::GpuMat maskGpu(mask);
00368 fast_(imgGpu, maskGpu, keypoints);
00369 }
00370 void computeDescriptors( const cv::Mat& image,
00371 std::vector<cv::KeyPoint>& keypoints,
00372 cv::Mat& descriptors)
00373 {
00374 UERROR("GPUFAST:computeDescriptors() Should not be used!");
00375 }
00376
00377 private:
00378 cv::gpu::FAST_GPU fast_;
00379 };
00380
00381 class GPUORB : public GPUFeature2D
00382 {
00383 public:
00384 GPUORB(int nFeatures = Settings::defaultFeature2D_ORB_nFeatures(),
00385 float scaleFactor = Settings::defaultFeature2D_ORB_scaleFactor(),
00386 int nLevels = Settings::defaultFeature2D_ORB_nLevels(),
00387 int edgeThreshold = Settings::defaultFeature2D_ORB_edgeThreshold(),
00388 int firstLevel = Settings::defaultFeature2D_ORB_firstLevel(),
00389 int WTA_K = Settings::defaultFeature2D_ORB_WTA_K(),
00390 int scoreType = Settings::defaultFeature2D_ORB_scoreType(),
00391 int patchSize = Settings::defaultFeature2D_ORB_patchSize(),
00392 int fastThreshold = Settings::defaultFeature2D_Fast_threshold(),
00393 bool fastNonmaxSupression = Settings::defaultFeature2D_Fast_nonmaxSuppression()) :
00394 orb_(nFeatures,
00395 scaleFactor,
00396 nLevels,
00397 edgeThreshold ,
00398 firstLevel,
00399 WTA_K,
00400 scoreType,
00401 patchSize)
00402 {
00403 orb_.setFastParams(fastThreshold, fastNonmaxSupression);
00404 }
00405 virtual ~GPUORB() {}
00406
00407 protected:
00408 void detectKeypoints(const cv::Mat & image,
00409 std::vector<cv::KeyPoint> & keypoints,
00410 const cv::Mat & mask = cv::Mat())
00411 {
00412 cv::gpu::GpuMat imgGpu(image);
00413 cv::gpu::GpuMat maskGpu(mask);
00414 try
00415 {
00416 orb_(imgGpu, maskGpu, keypoints);
00417 }
00418 catch(cv::Exception &e)
00419 {
00420 UERROR("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
00421 e.msg.c_str(),
00422 image.cols,
00423 image.rows);
00424 }
00425 }
00426
00427 void computeDescriptors( const cv::Mat& image,
00428 std::vector<cv::KeyPoint>& keypoints,
00429 cv::Mat& descriptors)
00430 {
00431 std::vector<float> d;
00432 cv::gpu::GpuMat imgGpu(image);
00433 cv::gpu::GpuMat descriptorsGPU;
00434 try
00435 {
00436 orb_(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU);
00437 }
00438 catch(cv::Exception &e)
00439 {
00440 UERROR("GPUORB error: %s \n(If something about matrix size, the image/object may be too small (%d,%d).)",
00441 e.msg.c_str(),
00442 image.cols,
00443 image.rows);
00444 }
00445
00446 if (descriptorsGPU.empty())
00447 descriptors = cv::Mat();
00448 else
00449 {
00450 UASSERT(descriptorsGPU.type() == CV_8U);
00451 descriptors = cv::Mat(descriptorsGPU.size(), CV_8U);
00452 descriptorsGPU.download(descriptors);
00453 }
00454 }
00455 private:
00456 cv::gpu::ORB_GPU orb_;
00457 };
00458
00459 KeypointDetector * Settings::createKeypointDetector()
00460 {
00461 cv::FeatureDetector * detector = 0;
00462 GPUFeature2D * detectorGPU = 0;
00463 QString str = getFeature2D_1Detector();
00464 QStringList split = str.split(':');
00465 if(split.size()==2)
00466 {
00467 bool ok = false;
00468 int index = split.first().toInt(&ok);
00469 if(ok)
00470 {
00471 QStringList strategies = split.last().split(';');
00472
00473 if(strategies.size() == 9 && index>=0 && index<9)
00474 {
00475
00476 #if FINDOBJECT_NONFREE == 0
00477
00478 if(strategies.at(index).compare("SIFT") == 0 ||
00479 strategies.at(index).compare("SURF") == 0)
00480 {
00481 index = Settings::defaultFeature2D_1Detector().split(':').first().toInt();
00482 UERROR("Find-Object is not built with OpenCV nonfree module so "
00483 "SIFT/SURF cannot be used! Using default \"%s\" instead.",
00484 strategies.at(index).toStdString().c_str());
00485
00486 }
00487 #endif
00488
00489 if(strategies.at(index).compare("Dense") == 0)
00490 {
00491 detector = new cv::DenseFeatureDetector(
00492 getFeature2D_Dense_initFeatureScale(),
00493 getFeature2D_Dense_featureScaleLevels(),
00494 getFeature2D_Dense_featureScaleMul(),
00495 getFeature2D_Dense_initXyStep(),
00496 getFeature2D_Dense_initImgBound(),
00497 getFeature2D_Dense_varyXyStepWithScale(),
00498 getFeature2D_Dense_varyImgBoundWithScale());
00499 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00500 }
00501 else if(strategies.at(index).compare("Fast") == 0)
00502 {
00503 if(getFeature2D_Fast_gpu() && cv::gpu::getCudaEnabledDeviceCount())
00504 {
00505 detectorGPU = new GPUFAST(
00506 getFeature2D_Fast_threshold(),
00507 getFeature2D_Fast_nonmaxSuppression());
00508 UDEBUG("type=%s GPU", strategies.at(index).toStdString().c_str());
00509 }
00510 else
00511 {
00512 detector = new cv::FastFeatureDetector(
00513 getFeature2D_Fast_threshold(),
00514 getFeature2D_Fast_nonmaxSuppression());
00515 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00516 }
00517 }
00518 else if(strategies.at(index).compare("GFTT") == 0)
00519 {
00520 detector = new cv::GFTTDetector(
00521 getFeature2D_GFTT_maxCorners(),
00522 getFeature2D_GFTT_qualityLevel(),
00523 getFeature2D_GFTT_minDistance(),
00524 getFeature2D_GFTT_blockSize(),
00525 getFeature2D_GFTT_useHarrisDetector(),
00526 getFeature2D_GFTT_k());
00527 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00528 }
00529 else if(strategies.at(index).compare("MSER") == 0)
00530 {
00531 detector = new cv::MSER(
00532 getFeature2D_MSER_delta(),
00533 getFeature2D_MSER_minArea(),
00534 getFeature2D_MSER_maxArea(),
00535 getFeature2D_MSER_maxVariation(),
00536 getFeature2D_MSER_minDiversity(),
00537 getFeature2D_MSER_maxEvolution(),
00538 getFeature2D_MSER_areaThreshold(),
00539 getFeature2D_MSER_minMargin(),
00540 getFeature2D_MSER_edgeBlurSize());
00541 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00542 }
00543 else if(strategies.at(index).compare("ORB") == 0)
00544 {
00545 if(getFeature2D_ORB_gpu() && cv::gpu::getCudaEnabledDeviceCount())
00546 {
00547 detectorGPU = new GPUORB(
00548 getFeature2D_ORB_nFeatures(),
00549 getFeature2D_ORB_scaleFactor(),
00550 getFeature2D_ORB_nLevels(),
00551 getFeature2D_ORB_edgeThreshold(),
00552 getFeature2D_ORB_firstLevel(),
00553 getFeature2D_ORB_WTA_K(),
00554 getFeature2D_ORB_scoreType(),
00555 getFeature2D_ORB_patchSize(),
00556 getFeature2D_Fast_threshold(),
00557 getFeature2D_Fast_nonmaxSuppression());
00558 UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
00559 }
00560 else
00561 {
00562 detector = new cv::ORB(
00563 getFeature2D_ORB_nFeatures(),
00564 getFeature2D_ORB_scaleFactor(),
00565 getFeature2D_ORB_nLevels(),
00566 getFeature2D_ORB_edgeThreshold(),
00567 getFeature2D_ORB_firstLevel(),
00568 getFeature2D_ORB_WTA_K(),
00569 getFeature2D_ORB_scoreType(),
00570 getFeature2D_ORB_patchSize());
00571 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00572 }
00573 }
00574 else if(strategies.at(index).compare("Star") == 0)
00575 {
00576 detector = new cv::StarFeatureDetector(
00577 getFeature2D_Star_maxSize(),
00578 getFeature2D_Star_responseThreshold(),
00579 getFeature2D_Star_lineThresholdProjected(),
00580 getFeature2D_Star_lineThresholdBinarized(),
00581 getFeature2D_Star_suppressNonmaxSize());
00582 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00583 }
00584 else if(strategies.at(index).compare("BRISK") == 0)
00585 {
00586 detector = new cv::BRISK(
00587 getFeature2D_BRISK_thresh(),
00588 getFeature2D_BRISK_octaves(),
00589 getFeature2D_BRISK_patternScale());
00590 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00591 }
00592 #if FINDOBJECT_NONFREE == 1
00593 else if(strategies.at(index).compare("SIFT") == 0)
00594 {
00595 detector = new cv::SIFT(
00596 getFeature2D_SIFT_nfeatures(),
00597 getFeature2D_SIFT_nOctaveLayers(),
00598 getFeature2D_SIFT_contrastThreshold(),
00599 getFeature2D_SIFT_edgeThreshold(),
00600 getFeature2D_SIFT_sigma());
00601 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00602 }
00603 else if(strategies.at(index).compare("SURF") == 0)
00604 {
00605 if(getFeature2D_SURF_gpu() && cv::gpu::getCudaEnabledDeviceCount())
00606 {
00607 detectorGPU = new GPUSURF(
00608 getFeature2D_SURF_hessianThreshold(),
00609 getFeature2D_SURF_nOctaves(),
00610 getFeature2D_SURF_nOctaveLayers(),
00611 getFeature2D_SURF_extended(),
00612 getFeature2D_SURF_keypointsRatio(),
00613 getFeature2D_SURF_upright());
00614 UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
00615 }
00616 else
00617 {
00618 detector = new cv::SURF(
00619 getFeature2D_SURF_hessianThreshold(),
00620 getFeature2D_SURF_nOctaves(),
00621 getFeature2D_SURF_nOctaveLayers(),
00622 getFeature2D_SURF_extended(),
00623 getFeature2D_SURF_upright());
00624 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00625 }
00626 }
00627 #endif
00628 }
00629 }
00630 }
00631
00632 UASSERT(detectorGPU!=0 || detector!=0);
00633 if(detectorGPU)
00634 {
00635 return new KeypointDetector(detectorGPU);
00636 }
00637 else
00638 {
00639 return new KeypointDetector(detector);
00640 }
00641 }
00642
00643 DescriptorExtractor * Settings::createDescriptorExtractor()
00644 {
00645 cv::DescriptorExtractor * extractor = 0;
00646 GPUFeature2D * extractorGPU = 0;
00647 QString str = getFeature2D_2Descriptor();
00648 QStringList split = str.split(':');
00649 if(split.size()==2)
00650 {
00651 bool ok = false;
00652 int index = split.first().toInt(&ok);
00653 if(ok)
00654 {
00655 QStringList strategies = split.last().split(';');
00656 if(strategies.size() == 6 && index>=0 && index<6)
00657 {
00658
00659 #if FINDOBJECT_NONFREE == 0
00660
00661 if(strategies.at(index).compare("SIFT") == 0 ||
00662 strategies.at(index).compare("SURF") == 0)
00663 {
00664 index = Settings::defaultFeature2D_2Descriptor().split(':').first().toInt();
00665 UERROR("Find-Object is not built with OpenCV nonfree module so "
00666 "SIFT/SURF cannot be used! Using default \"%s\" instead.",
00667 strategies.at(index).toStdString().c_str());
00668
00669 }
00670 #endif
00671
00672 if(strategies.at(index).compare("Brief") == 0)
00673 {
00674 extractor = new cv::BriefDescriptorExtractor(
00675 getFeature2D_Brief_bytes());
00676 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00677 }
00678 else if(strategies.at(index).compare("ORB") == 0)
00679 {
00680 if(getFeature2D_ORB_gpu() && cv::gpu::getCudaEnabledDeviceCount())
00681 {
00682 extractorGPU = new GPUORB(
00683 getFeature2D_ORB_nFeatures(),
00684 getFeature2D_ORB_scaleFactor(),
00685 getFeature2D_ORB_nLevels(),
00686 getFeature2D_ORB_edgeThreshold(),
00687 getFeature2D_ORB_firstLevel(),
00688 getFeature2D_ORB_WTA_K(),
00689 getFeature2D_ORB_scoreType(),
00690 getFeature2D_ORB_patchSize(),
00691 getFeature2D_Fast_threshold(),
00692 getFeature2D_Fast_nonmaxSuppression());
00693 UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
00694 }
00695 else
00696 {
00697 extractor = new cv::ORB(
00698 getFeature2D_ORB_nFeatures(),
00699 getFeature2D_ORB_scaleFactor(),
00700 getFeature2D_ORB_nLevels(),
00701 getFeature2D_ORB_edgeThreshold(),
00702 getFeature2D_ORB_firstLevel(),
00703 getFeature2D_ORB_WTA_K(),
00704 getFeature2D_ORB_scoreType(),
00705 getFeature2D_ORB_patchSize());
00706 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00707 }
00708 }
00709 else if(strategies.at(index).compare("BRISK") == 0)
00710 {
00711 extractor = new cv::BRISK(
00712 getFeature2D_BRISK_thresh(),
00713 getFeature2D_BRISK_octaves(),
00714 getFeature2D_BRISK_patternScale());
00715 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00716 }
00717 else if(strategies.at(index).compare("FREAK") == 0)
00718 {
00719 extractor = new cv::FREAK(
00720 getFeature2D_FREAK_orientationNormalized(),
00721 getFeature2D_FREAK_scaleNormalized(),
00722 getFeature2D_FREAK_patternScale(),
00723 getFeature2D_FREAK_nOctaves());
00724 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00725 }
00726 #if FINDOBJECT_NONFREE == 1
00727 else if(strategies.at(index).compare("SIFT") == 0)
00728 {
00729 extractor = new cv::SIFT(
00730 getFeature2D_SIFT_nfeatures(),
00731 getFeature2D_SIFT_nOctaveLayers(),
00732 getFeature2D_SIFT_contrastThreshold(),
00733 getFeature2D_SIFT_edgeThreshold(),
00734 getFeature2D_SIFT_sigma());
00735 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00736 }
00737 else if(strategies.at(index).compare("SURF") == 0)
00738 {
00739 if(getFeature2D_SURF_gpu() && cv::gpu::getCudaEnabledDeviceCount())
00740 {
00741 extractorGPU = new GPUSURF(
00742 getFeature2D_SURF_hessianThreshold(),
00743 getFeature2D_SURF_nOctaves(),
00744 getFeature2D_SURF_nOctaveLayers(),
00745 getFeature2D_SURF_extended(),
00746 getFeature2D_SURF_keypointsRatio(),
00747 getFeature2D_SURF_upright());
00748 UDEBUG("type=%s (GPU)", strategies.at(index).toStdString().c_str());
00749 }
00750 else
00751 {
00752 extractor = new cv::SURF(
00753 getFeature2D_SURF_hessianThreshold(),
00754 getFeature2D_SURF_nOctaves(),
00755 getFeature2D_SURF_nOctaveLayers(),
00756 getFeature2D_SURF_extended(),
00757 getFeature2D_SURF_upright());
00758 UDEBUG("type=%s", strategies.at(index).toStdString().c_str());
00759 }
00760 }
00761 #endif
00762 }
00763 }
00764 }
00765
00766 UASSERT(extractorGPU!=0 || extractor!=0);
00767 if(extractorGPU)
00768 {
00769 return new DescriptorExtractor(extractorGPU);
00770 }
00771 else
00772 {
00773 return new DescriptorExtractor(extractor);
00774 }
00775 }
00776
00777 QString Settings::currentDetectorType()
00778 {
00779 int index = getFeature2D_1Detector().split(':').first().toInt();
00780 return getFeature2D_1Detector().split(':').last().split(';').at(index);
00781 }
00782
00783 QString Settings::currentDescriptorType()
00784 {
00785 int index = getFeature2D_2Descriptor().split(':').first().toInt();
00786 return getFeature2D_2Descriptor().split(':').last().split(';').at(index);
00787 }
00788
00789 QString Settings::currentNearestNeighborType()
00790 {
00791 int index = getNearestNeighbor_1Strategy().split(':').first().toInt();
00792 return getNearestNeighbor_1Strategy().split(':').last().split(';').at(index);
00793 }
00794
00795 bool Settings::isBruteForceNearestNeighbor()
00796 {
00797 bool bruteForce = false;
00798 QString str = getNearestNeighbor_1Strategy();
00799 QStringList split = str.split(':');
00800 if(split.size()==2)
00801 {
00802 bool ok = false;
00803 int index = split.first().toInt(&ok);
00804 if(ok)
00805 {
00806 QStringList strategies = split.last().split(';');
00807 if(strategies.size() >= 7 && index == 6)
00808 {
00809 bruteForce = true;
00810 }
00811 }
00812 }
00813 return bruteForce;
00814 }
00815
00816 cv::flann::IndexParams * Settings::createFlannIndexParams()
00817 {
00818 cv::flann::IndexParams * params = 0;
00819 QString str = getNearestNeighbor_1Strategy();
00820 QStringList split = str.split(':');
00821 if(split.size()==2)
00822 {
00823 bool ok = false;
00824 int index = split.first().toInt(&ok);
00825 if(ok)
00826 {
00827 QStringList strategies = split.last().split(';');
00828 if(strategies.size() >= 6 && index>=0 && index<6)
00829 {
00830 switch(index)
00831 {
00832 case 0:
00833 if(strategies.at(index).compare("Linear") == 0)
00834 {
00835 UDEBUG("type=%s", "Linear");
00836 params = new cv::flann::LinearIndexParams();
00837 }
00838 break;
00839 case 1:
00840 if(strategies.at(index).compare("KDTree") == 0)
00841 {
00842 UDEBUG("type=%s", "KDTree");
00843 params = new cv::flann::KDTreeIndexParams(
00844 getNearestNeighbor_KDTree_trees());
00845 }
00846 break;
00847 case 2:
00848 if(strategies.at(index).compare("KMeans") == 0)
00849 {
00850 cvflann::flann_centers_init_t centers_init = cvflann::FLANN_CENTERS_RANDOM;
00851 QString str = getNearestNeighbor_KMeans_centers_init();
00852 QStringList split = str.split(':');
00853 if(split.size()==2)
00854 {
00855 bool ok = false;
00856 int index = split.first().toInt(&ok);
00857 if(ok)
00858 {
00859 centers_init = (cvflann::flann_centers_init_t)index;
00860 }
00861 }
00862 UDEBUG("type=%s", "KMeans");
00863 params = new cv::flann::KMeansIndexParams(
00864 getNearestNeighbor_KMeans_branching(),
00865 getNearestNeighbor_KMeans_iterations(),
00866 centers_init,
00867 getNearestNeighbor_KMeans_cb_index());
00868 }
00869 break;
00870 case 3:
00871 if(strategies.at(index).compare("Composite") == 0)
00872 {
00873 cvflann::flann_centers_init_t centers_init = cvflann::FLANN_CENTERS_RANDOM;
00874 QString str = getNearestNeighbor_Composite_centers_init();
00875 QStringList split = str.split(':');
00876 if(split.size()==2)
00877 {
00878 bool ok = false;
00879 int index = split.first().toInt(&ok);
00880 if(ok)
00881 {
00882 centers_init = (cvflann::flann_centers_init_t)index;
00883 }
00884 }
00885 UDEBUG("type=%s", "Composite");
00886 params = new cv::flann::CompositeIndexParams(
00887 getNearestNeighbor_Composite_trees(),
00888 getNearestNeighbor_Composite_branching(),
00889 getNearestNeighbor_Composite_iterations(),
00890 centers_init,
00891 getNearestNeighbor_Composite_cb_index());
00892 }
00893 break;
00894 case 4:
00895 if(strategies.at(index).compare("Autotuned") == 0)
00896 {
00897 UDEBUG("type=%s", "Autotuned");
00898 params = new cv::flann::AutotunedIndexParams(
00899 getNearestNeighbor_Autotuned_target_precision(),
00900 getNearestNeighbor_Autotuned_build_weight(),
00901 getNearestNeighbor_Autotuned_memory_weight(),
00902 getNearestNeighbor_Autotuned_sample_fraction());
00903 }
00904 break;
00905 case 5:
00906 if(strategies.at(index).compare("Lsh") == 0)
00907 {
00908 UDEBUG("type=%s", "Lsh");
00909 params = new cv::flann::LshIndexParams(
00910 getNearestNeighbor_Lsh_table_number(),
00911 getNearestNeighbor_Lsh_key_size(),
00912 getNearestNeighbor_Lsh_multi_probe_level());
00913
00914 }
00915 break;
00916 default:
00917 break;
00918 }
00919 }
00920 }
00921 }
00922 if(!params)
00923 {
00924 UERROR("NN strategy not found !? Using default KDTRee...");
00925 params = new cv::flann::KDTreeIndexParams();
00926 }
00927 return params ;
00928 }
00929
00930 cvflann::flann_distance_t Settings::getFlannDistanceType()
00931 {
00932 cvflann::flann_distance_t distance = cvflann::FLANN_DIST_L2;
00933 QString str = getNearestNeighbor_2Distance_type();
00934 QStringList split = str.split(':');
00935 if(split.size()==2)
00936 {
00937 bool ok = false;
00938 int index = split.first().toInt(&ok);
00939 if(ok)
00940 {
00941 QStringList strategies = split.last().split(';');
00942 if(strategies.size() == 9 && index>=0 && index<=8)
00943 {
00944 distance = (cvflann::flann_distance_t)(index+1);
00945 }
00946 }
00947 }
00948 return distance;
00949 }
00950
00951 cv::flann::SearchParams Settings::getFlannSearchParams()
00952 {
00953 return cv::flann::SearchParams(
00954 getNearestNeighbor_search_checks(),
00955 getNearestNeighbor_search_eps(),
00956 getNearestNeighbor_search_sorted());
00957 }
00958
00959 int Settings::getHomographyMethod()
00960 {
00961 int method = cv::RANSAC;
00962 QString str = getHomography_method();
00963 QStringList split = str.split(':');
00964 if(split.size()==2)
00965 {
00966 bool ok = false;
00967 int index = split.first().toInt(&ok);
00968 if(ok)
00969 {
00970 QStringList strategies = split.last().split(';');
00971 if(strategies.size() == 2 && index>=0 && index<2)
00972 {
00973 switch(method)
00974 {
00975 case 0:
00976 method = cv::LMEDS;
00977 break;
00978 default:
00979 method = cv::RANSAC;
00980 break;
00981 }
00982 }
00983 }
00984 }
00985 UDEBUG("method=%d", method);
00986 return method;
00987 }
00988
00989 KeypointDetector::KeypointDetector(cv::FeatureDetector * featureDetector) :
00990 featureDetector_(featureDetector),
00991 gpuFeature2D_(0)
00992 {
00993 UASSERT(featureDetector_!=0);
00994 }
00995 KeypointDetector::KeypointDetector(GPUFeature2D * gpuFeature2D) :
00996 featureDetector_(0),
00997 gpuFeature2D_(gpuFeature2D)
00998 {
00999 UASSERT(gpuFeature2D_!=0);
01000 }
01001 void KeypointDetector::detect(const cv::Mat & image,
01002 std::vector<cv::KeyPoint> & keypoints,
01003 const cv::Mat & mask)
01004 {
01005 if(featureDetector_)
01006 {
01007 featureDetector_->detect(image, keypoints, mask);
01008 }
01009 else
01010 {
01011 gpuFeature2D_->detectKeypoints(image, keypoints, mask);
01012 }
01013 }
01014
01015 DescriptorExtractor::DescriptorExtractor(cv::DescriptorExtractor * descriptorExtractor) :
01016 descriptorExtractor_(descriptorExtractor),
01017 gpuFeature2D_(0)
01018 {
01019 UASSERT(descriptorExtractor_!=0);
01020 }
01021 DescriptorExtractor::DescriptorExtractor(GPUFeature2D * gpuFeature2D) :
01022 descriptorExtractor_(0),
01023 gpuFeature2D_(gpuFeature2D)
01024 {
01025 UASSERT(gpuFeature2D_!=0);
01026 }
01027 void DescriptorExtractor::compute(const cv::Mat & image,
01028 std::vector<cv::KeyPoint> & keypoints,
01029 cv::Mat & descriptors)
01030 {
01031 if(descriptorExtractor_)
01032 {
01033 descriptorExtractor_->compute(image, keypoints, descriptors);
01034 }
01035 else
01036 {
01037 gpuFeature2D_->computeDescriptors(image, keypoints, descriptors);
01038 }
01039 }
01040
01041 }