Vocabulary.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/Settings.h"
29 
31 #include "Compression.h"
32 #include "Vocabulary.h"
33 #include <QtCore/QVector>
34 #include <QDataStream>
35 #include <QTime>
36 #include <stdio.h>
37 #if CV_MAJOR_VERSION < 3
38 #include <opencv2/gpu/gpu.hpp>
39 #define CVCUDA cv::gpu
40 #else
41 #include <opencv2/core/cuda.hpp>
42 #define CVCUDA cv::cuda
43 #ifdef HAVE_OPENCV_CUDAFEATURES2D
44 #include <opencv2/cudafeatures2d.hpp>
45 #endif
46 #endif
47 
48 namespace find_object {
49 
51 {
52 }
53 
55 {
56 }
57 
59 {
60  wordToObjects_.clear();
61  notIndexedDescriptors_ = cv::Mat();
62  notIndexedWordIds_.clear();
63 
64  if(Settings::getGeneral_vocabularyFixed() && Settings::getGeneral_invertedSearch())
65  {
66  this->update(); // if vocabulary structure has changed
67 
68  // If the dictionary is fixed, don't clear indexed descriptors
69  return;
70  }
71 
72  indexedDescriptors_ = cv::Mat();
73 }
74 
75 void Vocabulary::save(QDataStream & streamSessionPtr, bool saveVocabularyOnly) const
76 {
77  // save index
78  if(saveVocabularyOnly)
79  {
80  QMultiMap<int, int> dummy;
81  streamSessionPtr << dummy;
82  }
83  else
84  {
85  UINFO("Saving %d object references...", wordToObjects_.size());
86  streamSessionPtr << wordToObjects_;
87  }
88 
89  // save words
90  qint64 rawDataSize = indexedDescriptors_.rows * indexedDescriptors_.cols * indexedDescriptors_.elemSize();
91  UINFO("Compressing words... (%dx%d, %d MB)", indexedDescriptors_.rows, indexedDescriptors_.cols, rawDataSize/(1024*1024));
92  std::vector<unsigned char> bytes = compressData(indexedDescriptors_);
93  qint64 dataSize = bytes.size();
94  UINFO("Compressed = %d MB", dataSize/(1024*1024));
95  int old = 0;
96  if(dataSize <= std::numeric_limits<int>::max())
97  {
98  // old: rows, cols, type
99  streamSessionPtr << old << old << old << dataSize;
100  streamSessionPtr << QByteArray::fromRawData((const char*)bytes.data(), dataSize);
101  }
102  else
103  {
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));
106  // old: rows, cols, type, dataSize
107  streamSessionPtr << old << old << old << old;
108  streamSessionPtr << QByteArray(); // empty
109  }
110 }
111 
112 void Vocabulary::load(QDataStream & streamSessionPtr, bool loadVocabularyOnly)
113 {
114  // load index
115  if(loadVocabularyOnly)
116  {
117  QMultiMap<int, int> dummy;
118  streamSessionPtr >> dummy;
119  // clear index
120  wordToObjects_.clear();
121  }
122  else
123  {
124  UINFO("Loading words to objects references...");
125  streamSessionPtr >> wordToObjects_;
126  UINFO("Loaded %d object references...", wordToObjects_.size());
127  }
128 
129  // load words
130  int rows,cols,type;
131  qint64 dataSize;
132  streamSessionPtr >> rows >> cols >> type >> dataSize;
133  if(rows == 0 && cols == 0 && type == 0)
134  {
135  // compressed vocabulary
136  UINFO("Loading words... (compressed format: %d MB)", dataSize/(1024*1024));
137  UASSERT(dataSize <= std::numeric_limits<int>::max());
138  QByteArray data;
139  streamSessionPtr >> data;
140  UINFO("Uncompress vocabulary...");
141  indexedDescriptors_ = uncompressData((unsigned const char*)data.data(), dataSize);
142  UINFO("Words: %dx%d (%d MB)", indexedDescriptors_.rows, indexedDescriptors_.cols,
143  (indexedDescriptors_.rows * indexedDescriptors_.cols * indexedDescriptors_.elemSize()) / (1024*1024));
144  }
145  else
146  {
147  // old raw format
148  UINFO("Loading words... (old format: %dx%d (%d MB))", rows, cols, dataSize/(1024*1024));
149  QByteArray data;
150  streamSessionPtr >> data;
151  UINFO("Allocate memory...");
152  if(data.size())
153  {
154  indexedDescriptors_ = cv::Mat(rows, cols, type, data.data()).clone();
155  }
156  else if(dataSize)
157  {
158  UERROR("Error reading vocabulary data...");
159  }
160  }
161 
162  UINFO("Update vocabulary index...");
163  update();
164 }
165 
166 bool Vocabulary::save(const QString & filename) const
167 {
168  // save descriptors
169  cv::FileStorage fs(filename.toStdString(), cv::FileStorage::WRITE);
170  if(fs.isOpened())
171  {
172  fs << "Descriptors" << indexedDescriptors_;
173  return true;
174  }
175  else
176  {
177  UERROR("Failed to open vocabulary file \"%s\"", filename.toStdString().c_str());
178  }
179  return false;
180 }
181 
182 bool Vocabulary::load(const QString & filename)
183 {
184  // save descriptors
185  cv::FileStorage fs(filename.toStdString(), cv::FileStorage::READ);
186  if(fs.isOpened())
187  {
188  cv::Mat tmp;
189  fs["Descriptors"] >> tmp;
190 
191  if(!tmp.empty())
192  {
193  // clear index
194  wordToObjects_.clear();
195  indexedDescriptors_ = tmp;
196  update();
197  return true;
198  }
199  else
200  {
201  UERROR("Failed to read \"Descriptors\" matrix field (doesn't exist or is empty) from vocabulary file \"%s\"", filename.toStdString().c_str());
202  }
203  }
204  else
205  {
206  UERROR("Failed to open vocabulary file \"%s\"", filename.toStdString().c_str());
207  }
208  return false;
209 }
210 
211 QMultiMap<int, int> Vocabulary::addWords(const cv::Mat & descriptorsIn, int objectId)
212 {
213  QMultiMap<int, int> words;
214  if (descriptorsIn.empty())
215  {
216  return words;
217  }
218 
219  cv::Mat descriptors;
220  if(descriptorsIn.type() == CV_8U && Settings::getNearestNeighbor_7ConvertBinToFloat())
221  {
222  descriptorsIn.convertTo(descriptors, CV_32F);
223  }
224  else
225  {
226  descriptors = descriptorsIn;
227  }
228 
229  if(Settings::getGeneral_vocabularyIncremental() || Settings::getGeneral_vocabularyFixed())
230  {
231  int k = 2;
232  cv::Mat results;
233  cv::Mat dists;
234 
235  bool globalSearch = false;
236  if(!indexedDescriptors_.empty() && indexedDescriptors_.rows >= (int)k)
237  {
238  if(indexedDescriptors_.type() != descriptors.type() || indexedDescriptors_.cols != descriptors.cols)
239  {
240  if(Settings::getGeneral_vocabularyFixed())
241  {
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.",
243  descriptors.type(), descriptors.cols, indexedDescriptors_.type(), indexedDescriptors_.cols);
244  return words;
245  }
246  else
247  {
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)!",
249  descriptors.type(), descriptors.cols, indexedDescriptors_.type(), indexedDescriptors_.cols);
250  }
251  }
252 
253  this->search(descriptors, results, dists, k);
254 
255  if( dists.type() == CV_32S )
256  {
257  cv::Mat temp;
258  dists.convertTo(temp, CV_32F);
259  dists = temp;
260  }
261 
262  globalSearch = true;
263  }
264 
265  if(!Settings::getGeneral_vocabularyFixed())
266  {
267  notIndexedWordIds_.reserve(notIndexedWordIds_.size() + descriptors.rows);
268  notIndexedDescriptors_.reserve(notIndexedDescriptors_.rows + descriptors.rows);
269  }
270  int matches = 0;
271  for(int i = 0; i < descriptors.rows; ++i)
272  {
273  QMultiMap<float, int> fullResults; // nearest descriptors sorted by distance
274  if(notIndexedDescriptors_.rows)
275  {
276  UASSERT(notIndexedDescriptors_.type() == descriptors.type() && notIndexedDescriptors_.cols == descriptors.cols);
277 
278  // Check if this descriptor matches with a word not already added to the vocabulary
279  // Do linear search only
280  cv::Mat tmpResults;
281  cv::Mat tmpDists;
282  if(descriptors.type()==CV_8U)
283  {
284  //normType – One of NORM_L1, NORM_L2, NORM_HAMMING, NORM_HAMMING2. L1 and L2 norms are
285  // preferable choices for SIFT and SURF descriptors, NORM_HAMMING should be
286  // used with ORB, BRISK and BRIEF, NORM_HAMMING2 should be used with ORB
287  // when WTA_K==3 or 4 (see ORB::ORB constructor description).
288  int normType = cv::NORM_HAMMING;
289  if(Settings::currentDescriptorType().compare("ORB") &&
290  (Settings::getFeature2D_ORB_WTA_K()==3 || Settings::getFeature2D_ORB_WTA_K()==4))
291  {
292  normType = cv::NORM_HAMMING2;
293  }
294 
295  cv::batchDistance( descriptors.row(i),
297  tmpDists,
298  CV_32S,
299  tmpResults,
300  normType,
301  notIndexedDescriptors_.rows>=k?k:1,
302  cv::Mat(),
303  0,
304  false);
305  }
306  else
307  {
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);
311 #else
312  tmpIndex.build(notIndexedDescriptors_, cv::flann::LinearIndexParams(), cvflann::FLANN_DIST_L2);
313 #endif
314  tmpIndex.knnSearch(descriptors.row(i), tmpResults, tmpDists, notIndexedDescriptors_.rows>1?k:1, cvflann::FLANN_DIST_L2);
315  }
316 
317  if( tmpDists.type() == CV_32S )
318  {
319  cv::Mat temp;
320  tmpDists.convertTo(temp, CV_32F);
321  tmpDists = temp;
322  }
323 
324  for(int j = 0; j < tmpResults.cols; ++j)
325  {
326  if(tmpResults.at<int>(0,j) >= 0)
327  {
328  //printf("local i=%d, j=%d, tmpDist=%f tmpResult=%d\n", i ,j, tmpDists.at<float>(0,j), tmpResults.at<int>(0,j));
329  fullResults.insert(tmpDists.at<float>(0,j), notIndexedWordIds_.at(tmpResults.at<int>(0,j)));
330  }
331  }
332  }
333 
334  if(globalSearch)
335  {
336  for(int j=0; j<k; ++j)
337  {
338  if(results.at<int>(i,j) >= 0)
339  {
340  //printf("global i=%d, j=%d, dist=%f\n", i ,j, dists.at<float>(i,j));
341  fullResults.insert(dists.at<float>(i,j), results.at<int>(i,j));
342  }
343  }
344  }
345 
346  bool matched = false;
347  if(Settings::getNearestNeighbor_3nndrRatioUsed() &&
348  fullResults.size() >= 2 &&
349  fullResults.begin().key() <= Settings::getNearestNeighbor_4nndrRatio() * (++fullResults.begin()).key())
350  {
351  matched = true;
352  }
353  if((matched || !Settings::getNearestNeighbor_3nndrRatioUsed()) &&
354  Settings::getNearestNeighbor_5minDistanceUsed())
355  {
356  if(fullResults.begin().key() <= Settings::getNearestNeighbor_6minDistance())
357  {
358  matched = true;
359  }
360  else
361  {
362  matched = false;
363  }
364  }
365  if(!matched && !Settings::getNearestNeighbor_3nndrRatioUsed() && !Settings::getNearestNeighbor_5minDistanceUsed())
366  {
367  matched = true; // no criterion, match to the nearest descriptor
368  }
369 
370  if(matched)
371  {
372  words.insert(fullResults.begin().value(), i);
373  wordToObjects_.insert(fullResults.begin().value(), objectId);
374  ++matches;
375  }
376  else if(!Settings::getGeneral_invertedSearch() || !Settings::getGeneral_vocabularyFixed())
377  {
378  //concatenate new words
380  notIndexedDescriptors_.push_back(descriptors.row(i));
381  words.insert(notIndexedWordIds_.back(), i);
382  wordToObjects_.insert(notIndexedWordIds_.back(), objectId);
383  }
384  else
385  {
386  words.insert(-1, i); // invalid word
387  }
388  }
389  }
390  else
391  {
392  for(int i = 0; i < descriptors.rows; ++i)
393  {
394  wordToObjects_.insert(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i, objectId);
395  words.insert(indexedDescriptors_.rows + notIndexedDescriptors_.rows+i, i);
397  }
398 
399  //just concatenate descriptors
400  notIndexedDescriptors_.push_back(descriptors);
401  }
402  return words;
403 }
404 
406 {
407  if(!notIndexedDescriptors_.empty())
408  {
409  if(!indexedDescriptors_.empty())
410  {
412  indexedDescriptors_.type() == notIndexedDescriptors_.type() );
413  }
414 
415  //concatenate descriptors
417 
418  notIndexedDescriptors_ = cv::Mat();
419  notIndexedWordIds_.clear();
420  }
421 
423  {
424  cv::flann::IndexParams * params = Settings::createFlannIndexParams();
425 #if CV_MAJOR_VERSION == 2 and CV_MINOR_VERSION == 4 and CV_SUBMINOR_VERSION >= 12
426  flannIndex_.build(indexedDescriptors_, cv::Mat(), *params, Settings::getFlannDistanceType());
427 #else
429 #endif
430  delete params;
431  }
432 }
433 
434 void Vocabulary::search(const cv::Mat & descriptorsIn, cv::Mat & results, cv::Mat & dists, int k)
435 {
436  if(!indexedDescriptors_.empty())
437  {
438  cv::Mat descriptors;
439  if(descriptorsIn.type() == CV_8U && Settings::getNearestNeighbor_7ConvertBinToFloat())
440  {
441  descriptorsIn.convertTo(descriptors, CV_32F);
442  }
443  else
444  {
445  descriptors = descriptorsIn;
446  }
447 
448  UASSERT(descriptors.type() == indexedDescriptors_.type() && descriptors.cols == indexedDescriptors_.cols);
449 
451  {
452  std::vector<std::vector<cv::DMatch> > matches;
453  bool isL2NotSqr = false;
454  if(Settings::getNearestNeighbor_BruteForce_gpu() && CVCUDA::getCudaEnabledDeviceCount())
455  {
456  CVCUDA::GpuMat newDescriptorsGpu(descriptors);
457  CVCUDA::GpuMat lastDescriptorsGpu(indexedDescriptors_);
458 #if CV_MAJOR_VERSION < 3
459  if(indexedDescriptors_.type()==CV_8U)
460  {
461  CVCUDA::BruteForceMatcher_GPU<cv::Hamming> gpuMatcher;
462  gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
463  }
464  else
465  {
466  CVCUDA::BruteForceMatcher_GPU<cv::L2<float> > gpuMatcher;
467  gpuMatcher.knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
468  isL2NotSqr = true;
469  }
470 #else
471 #ifdef HAVE_OPENCV_CUDAFEATURES2D
472  cv::Ptr<cv::cuda::DescriptorMatcher> gpuMatcher;
473  if(indexedDescriptors_.type()==CV_8U)
474  {
475  gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_HAMMING);
476  gpuMatcher->knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
477  }
478  else
479  {
480  gpuMatcher = cv::cuda::DescriptorMatcher::createBFMatcher(cv::NORM_L2);
481  gpuMatcher->knnMatch(newDescriptorsGpu, lastDescriptorsGpu, matches, k);
482  isL2NotSqr = true;
483  }
484 #else
485  UERROR("OpenCV3 is not built with CUDAFEATURES2D module, cannot do brute force matching on GPU!");
486 #endif
487 #endif
488  }
489  else
490  {
491  cv::BFMatcher matcher(indexedDescriptors_.type()==CV_8U?cv::NORM_HAMMING:cv::NORM_L2SQR);
492  matcher.knnMatch(descriptors, indexedDescriptors_, matches, k);
493  }
494 
495  //convert back to matrix style
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)
499  {
500  for(int j=0; j<k; ++j)
501  {
502  results.at<int>(i, j) = matches[i].at(j).trainIdx;
503 
504  if(isL2NotSqr)
505  {
506  // Make sure we use L2SQR to match FLANN
507  dists.at<float>(i, j) = matches[i].at(j).distance*matches[i].at(j).distance;
508  }
509  else
510  {
511  dists.at<float>(i, j) = matches[i].at(j).distance;
512  }
513  }
514  }
515  }
516  else
517  {
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()));
523  }
524 
525  if( dists.type() == CV_32S )
526  {
527  cv::Mat temp;
528  dists.convertTo(temp, CV_32F);
529  dists = temp;
530  }
531  }
532 }
533 
534 } // namespace find_object
static cv::flann::IndexParams * createFlannIndexParams()
Definition: Settings.cpp:1533
cv::Mat notIndexedDescriptors_
Definition: Vocabulary.h:60
cv::Mat uncompressData(const unsigned char *bytes, unsigned long size)
Definition: Compression.cpp:45
QVector< int > notIndexedWordIds_
Definition: Vocabulary.h:62
static cvflann::flann_distance_t getFlannDistanceType()
Definition: Settings.cpp:1647
#define UFATAL(...)
#define UASSERT(condition)
cv::flann::Index flannIndex_
Definition: Vocabulary.h:58
QMultiMap< int, int > addWords(const cv::Mat &descriptors, int objectId)
Definition: Vocabulary.cpp:211
void search(const cv::Mat &descriptors, cv::Mat &results, cv::Mat &dists, int k)
Definition: Vocabulary.cpp:434
QMultiMap< int, int > wordToObjects_
Definition: Vocabulary.h:61
std::vector< unsigned char > compressData(const cv::Mat &data)
Definition: Compression.cpp:14
static QString currentDescriptorType()
Definition: Settings.cpp:1500
void load(QDataStream &streamSessionPtr, bool loadVocabularyOnly=false)
Definition: Vocabulary.cpp:112
static bool isBruteForceNearestNeighbor()
Definition: Settings.cpp:1512
void save(QDataStream &streamSessionPtr, bool saveVocabularyOnly=false) const
Definition: Vocabulary.cpp:75
#define UERROR(...)
ULogger class and convenient macros.
#define UINFO(...)


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