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


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 19:22:26