33 #include <QtCore/QVector>    34 #include <QDataStream>    37 #if CV_MAJOR_VERSION < 3    38 #include <opencv2/gpu/gpu.hpp>    39 #define CVCUDA cv::gpu    41 #include <opencv2/core/cuda.hpp>    42 #define CVCUDA cv::cuda    43 #ifdef HAVE_OPENCV_CUDAFEATURES2D    44 #include <opencv2/cudafeatures2d.hpp>    64         if(Settings::getGeneral_vocabularyFixed() && Settings::getGeneral_invertedSearch())
    78         if(saveVocabularyOnly)
    80                 QMultiMap<int, int> dummy;
    81                 streamSessionPtr << dummy;
    93         qint64 dataSize = bytes.size();
    94         UINFO(
"Compressed = %d MB", dataSize/(1024*1024));
    96         if(dataSize <= std::numeric_limits<int>::max())
    99                 streamSessionPtr << old << old << old << dataSize;
   100                 streamSessionPtr << QByteArray::fromRawData((
const char*)bytes.data(), dataSize);
   104                 UERROR(
"Vocabulary (compressed) is too large (%d MB) to be saved! Limit is 2 GB (based on max QByteArray size).",
   105                                 dataSize/(1024*1024));
   107                 streamSessionPtr << old << old << old << old;
   108                 streamSessionPtr << QByteArray(); 
   115         if(loadVocabularyOnly)
   117                 QMultiMap<int, int> dummy;
   118                 streamSessionPtr >> dummy;
   124                 UINFO(
"Loading words to objects references...");
   126                 UINFO(
"Loaded %d object references...", wordToObjects_.size());
   132         streamSessionPtr >> rows >> cols >> type >> dataSize;
   133         if(rows == 0 && cols == 0 && type == 0)
   136                 UINFO(
"Loading words... (compressed format: %d MB)", dataSize/(1024*1024));
   137                 UASSERT(dataSize <= std::numeric_limits<int>::max());
   139                 streamSessionPtr >> data;
   140                 UINFO(
"Uncompress vocabulary...");
   148                 UINFO(
"Loading words... (old format: %dx%d (%d MB))", rows, cols, dataSize/(1024*1024));
   150                 streamSessionPtr >> data;
   151                 UINFO(
"Allocate memory...");
   158                         UERROR(
"Error reading vocabulary data...");
   162         UINFO(
"Update vocabulary index...");
   169         cv::FileStorage fs(filename.toStdString(), cv::FileStorage::WRITE);
   177                 UERROR(
"Failed to open vocabulary file \"%s\"", filename.toStdString().c_str());
   185         cv::FileStorage fs(filename.toStdString(), cv::FileStorage::READ);
   189                 fs[
"Descriptors"] >> tmp;
   201                         UERROR(
"Failed to read \"Descriptors\" matrix field (doesn't exist or is empty) from vocabulary file \"%s\"", filename.toStdString().c_str());
   206                 UERROR(
"Failed to open vocabulary file \"%s\"", filename.toStdString().c_str());
   213         QMultiMap<int, int> words;
   214         if (descriptorsIn.empty())
   220         if(descriptorsIn.type() == CV_8U && Settings::getNearestNeighbor_7ConvertBinToFloat())
   222                 descriptorsIn.convertTo(descriptors, CV_32F);
   226                 descriptors = descriptorsIn;
   229         if(Settings::getGeneral_vocabularyIncremental() || Settings::getGeneral_vocabularyFixed())
   235                 bool globalSearch = 
false;
   240                                 if(Settings::getGeneral_vocabularyFixed())
   242                                         UERROR(
"Descriptors (type=%d size=%d) to search in vocabulary are not the same type/size as those in the vocabulary (type=%d size=%d)! Empty words returned.",
   248                                         UFATAL(
"Descriptors (type=%d size=%d) to search in vocabulary are not the same type/size as those in the vocabulary (type=%d size=%d)!",
   253                         this->
search(descriptors, results, dists, k);
   255                         if( dists.type() == CV_32S )
   258                                 dists.convertTo(temp, CV_32F);
   265                 if(!Settings::getGeneral_vocabularyFixed())
   271                 for(
int i = 0; i < descriptors.rows; ++i)
   273                         QMultiMap<float, int> fullResults; 
   282                                 if(descriptors.type()==CV_8U)
   288                                         int normType = cv::NORM_HAMMING;
   290                                                 (Settings::getFeature2D_ORB_WTA_K()==3 || Settings::getFeature2D_ORB_WTA_K()==4))
   292                                                 normType = cv::NORM_HAMMING2;
   295                                         cv::batchDistance( descriptors.row(i),
   308                                         cv::flann::Index tmpIndex;
   309 #if CV_MAJOR_VERSION == 2 and CV_MINOR_VERSION == 4 and CV_SUBMINOR_VERSION >= 12   310                                         tmpIndex.build(
notIndexedDescriptors_, cv::Mat(), cv::flann::LinearIndexParams(), cvflann::FLANN_DIST_L2);
   314                                         tmpIndex.knnSearch(descriptors.row(i), tmpResults, tmpDists, 
notIndexedDescriptors_.rows>1?k:1, cvflann::FLANN_DIST_L2);
   317                                 if( tmpDists.type() == CV_32S )
   320                                         tmpDists.convertTo(temp, CV_32F);
   324                                 for(
int j = 0; j < tmpResults.cols; ++j)
   326                                         if(tmpResults.at<
int>(0,j) >= 0)
   329                                                 fullResults.insert(tmpDists.at<
float>(0,j), 
notIndexedWordIds_.at(tmpResults.at<
int>(0,j)));
   336                                 for(
int j=0; j<k; ++j)
   338                                         if(results.at<
int>(i,j) >= 0)
   341                                                 fullResults.insert(dists.at<
float>(i,j), results.at<
int>(i,j));
   346                         bool matched = 
false;
   347                         if(Settings::getNearestNeighbor_3nndrRatioUsed() &&
   348                            fullResults.size() >= 2 &&
   349                            fullResults.begin().key() <= Settings::getNearestNeighbor_4nndrRatio() * (++fullResults.begin()).key())
   353                         if((matched || !Settings::getNearestNeighbor_3nndrRatioUsed()) &&
   354                            Settings::getNearestNeighbor_5minDistanceUsed())
   356                                 if(fullResults.begin().key() <= Settings::getNearestNeighbor_6minDistance())
   365                         if(!matched && !Settings::getNearestNeighbor_3nndrRatioUsed() && !Settings::getNearestNeighbor_5minDistanceUsed())
   372                                 words.insert(fullResults.begin().value(), i);
   376                         else if(!Settings::getGeneral_invertedSearch() || !Settings::getGeneral_vocabularyFixed())
   392                 for(
int i = 0; i < descriptors.rows; ++i)
   425 #if CV_MAJOR_VERSION == 2 and CV_MINOR_VERSION == 4 and CV_SUBMINOR_VERSION >= 12   439                 if(descriptorsIn.type() == CV_8U && Settings::getNearestNeighbor_7ConvertBinToFloat())
   441                         descriptorsIn.convertTo(descriptors, CV_32F);
   445                         descriptors = descriptorsIn;
   452                         std::vector<std::vector<cv::DMatch> > matches;
   453                         bool isL2NotSqr = 
false;
   454                         if(Settings::getNearestNeighbor_BruteForce_gpu() && CVCUDA::getCudaEnabledDeviceCount())
   456                                 CVCUDA::GpuMat newDescriptorsGpu(descriptors);
   458 #if CV_MAJOR_VERSION < 3   461                                         CVCUDA::BruteForceMatcher_GPU<cv::Hamming> gpuMatcher;
   462                                         gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
   466                                         CVCUDA::BruteForceMatcher_GPU<cv::L2<float> > gpuMatcher;
   467                                         gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
   471 #ifdef HAVE_OPENCV_CUDAFEATURES2D   472                                 cv::Ptr<cv::cuda::DescriptorMatcher> gpuMatcher;
   475                                         gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_HAMMING);
   476                                         gpuMatcher->knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
   480                                         gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_L2);
   481                                         gpuMatcher->knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
   485                                 UERROR(
"OpenCV3 is not built with CUDAFEATURES2D module, cannot do brute force matching on GPU!");
   496                         results = cv::Mat((
int)matches.size(), k, CV_32SC1);
   497                         dists = cv::Mat((
int)matches.size(), k, CV_32FC1);
   498                         for(
unsigned int i=0; i<matches.size(); ++i)
   500                                 for(
int j=0; j<k; ++j)
   502                                         results.at<
int>(i, j) = matches[i].at(j).trainIdx;
   507                                                 dists.at<
float>(i, j) = matches[i].at(j).distance*matches[i].at(j).distance;
   511                                                 dists.at<
float>(i, j) = matches[i].at(j).distance;
   518                         flannIndex_.knnSearch(descriptors, results, dists, k,
   519                                         cv::flann::SearchParams(
   520                                                 Settings::getNearestNeighbor_search_checks(),
   521                                                 Settings::getNearestNeighbor_search_eps(),
   522                                                 Settings::getNearestNeighbor_search_sorted()));
   525                 if( dists.type() == CV_32S )
   528                         dists.convertTo(temp, CV_32F);
 static cv::flann::IndexParams * createFlannIndexParams()
cv::Mat indexedDescriptors_
cv::Mat notIndexedDescriptors_
cv::Mat uncompressData(const unsigned char *bytes, unsigned long size)
QVector< int > notIndexedWordIds_
static cvflann::flann_distance_t getFlannDistanceType()
#define UASSERT(condition)
cv::flann::Index flannIndex_
QMultiMap< int, int > addWords(const cv::Mat &descriptors, int objectId)
void search(const cv::Mat &descriptors, cv::Mat &results, cv::Mat &dists, int k)
QMultiMap< int, int > wordToObjects_
std::vector< unsigned char > compressData(const cv::Mat &data)
static QString currentDescriptorType()
void load(QDataStream &streamSessionPtr, bool loadVocabularyOnly=false)
static bool isBruteForceNearestNeighbor()
void save(QDataStream &streamSessionPtr, bool saveVocabularyOnly=false) const
ULogger class and convenient macros.