FindObject.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/FindObject.h"
29 #include "find_object/Settings.h"
31 #include "utilite/UConversion.h"
32 
33 #include "ObjSignature.h"
34 #include "utilite/UDirectory.h"
35 #include "Vocabulary.h"
36 
37 #include <QtCore/QThread>
38 #include <QtCore/QFileInfo>
39 #include <QtCore/QStringList>
40 #include <QtCore/QTime>
41 #include <QtCore/QDir>
42 #include <QGraphicsRectItem>
43 #include <stdio.h>
44 
45 #if CV_MAJOR_VERSION > 3
46 #include <opencv2/core/types_c.h>
47 #endif
48 
49 namespace find_object {
50 
51 FindObject::FindObject(bool keepImagesInRAM, QObject * parent) :
52  QObject(parent),
53  vocabulary_(new Vocabulary()),
54  detector_(Settings::createKeypointDetector()),
55  extractor_(Settings::createDescriptorExtractor()),
56  sessionModified_(false),
57  keepImagesInRAM_(keepImagesInRAM)
58 {
59  qRegisterMetaType<find_object::DetectionInfo>("find_object::DetectionInfo");
60  qRegisterMetaType<find_object::Header>("find_object::Header");
61  UASSERT(detector_ != 0 && extractor_ != 0);
62 
63  if(Settings::getGeneral_debug())
64  {
67  }
68  else
69  {
72  }
73 }
74 
76  delete detector_;
77  delete extractor_;
78  delete vocabulary_;
79  objectsDescriptors_.clear();
80 }
81 
82 bool FindObject::loadSession(const QString & path, const ParametersMap & customParameters)
83 {
84  if(QFile::exists(path) && !path.isEmpty() && QFileInfo(path).suffix().compare("bin") == 0)
85  {
86  QFile file(path);
87  file.open(QIODevice::ReadOnly);
88  QDataStream in(&file);
89 
90  ParametersMap parameters;
91 
92  // load parameters
93  in >> parameters;
94  for(QMap<QString, QVariant>::iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
95  {
96  QMap<QString, QVariant>::const_iterator cter = customParameters.find(iter.key());
97  if(cter != customParameters.constEnd())
98  {
99  Settings::setParameter(cter.key(), cter.value());
100  }
101  else
102  {
103  Settings::setParameter(iter.key(), iter.value());
104  }
105  }
106 
108 
109  // load vocabulary
110  vocabulary_->load(in);
111 
112  // load objects
113  while(!in.atEnd())
114  {
115  ObjSignature * obj = new ObjSignature();
116  obj->load(in, !keepImagesInRAM_);
117  if(obj->id() >= 0)
118  {
119  objects_.insert(obj->id(), obj);
120  }
121  else
122  {
123  UERROR("Failed to load and object!");
124  delete obj;
125  }
126  }
127  file.close();
128 
129  if(!Settings::getGeneral_invertedSearch())
130  {
131  // this will fill objectsDescriptors_ matrix
133  }
134  sessionModified_ = false;
135  return true;
136  }
137  else
138  {
139  UERROR("Invalid session file (should be *.bin): \"%s\"", path.toStdString().c_str());
140  }
141  return false;
142 }
143 
144 bool FindObject::saveSession(const QString & path)
145 {
146  if(!path.isEmpty() && QFileInfo(path).suffix().compare("bin") == 0)
147  {
148  QFile file(path);
149  file.open(QIODevice::WriteOnly);
150  QDataStream out(&file);
151 
152  // save parameters
153  out << Settings::getParameters();
154 
155  // save vocabulary
156  vocabulary_->save(out);
157 
158  // save objects
159  for(QMultiMap<int, ObjSignature*>::const_iterator iter=objects_.constBegin(); iter!=objects_.constEnd(); ++iter)
160  {
161  iter.value()->save(out);
162  }
163 
164  file.close();
165  sessionModified_ = false;
166  return true;
167  }
168  UERROR("Path \"%s\" not valid (should be *.bin)", path.toStdString().c_str());
169  return false;
170 }
171 
172 bool FindObject::saveVocabulary(const QString & filePath) const
173 {
174  if(!filePath.isEmpty() && QFileInfo(filePath).suffix().compare("bin") == 0)
175  {
176  QFile file(filePath);
177  file.open(QIODevice::WriteOnly);
178  QDataStream out(&file);
179 
180  // ignore parameters
181  out << ParametersMap();
182 
183  // save vocabulary
184  vocabulary_->save(out, true);
185 
186  file.close();
187  return true;
188  }
189  else
190  {
191  return vocabulary_->save(filePath);
192  }
193  return false;
194 }
195 
196 bool FindObject::loadVocabulary(const QString & filePath)
197 {
198  if(!Settings::getGeneral_vocabularyFixed() || !Settings::getGeneral_invertedSearch())
199  {
200  UWARN("Doesn't make sense to load a vocabulary if \"General/vocabularyFixed\" and \"General/invertedSearch\" are not enabled! It will "
201  "be cleared at the time the objects are updated.");
202  }
203 
204  if(QFile::exists(filePath) && !filePath.isEmpty() && QFileInfo(filePath).suffix().compare("bin") == 0)
205  {
206  //binary format (from session format)
207  QFile file(filePath);
208  file.open(QIODevice::ReadOnly);
209  QDataStream in(&file);
210 
211  ParametersMap parameters;
212  // ignore parameters
213  in >> parameters;
214 
215  // load vocabulary
216  vocabulary_->load(in, true);
217  file.close();
218 
219  return true;
220  }
221  else
222  {
223  //yaml/xml format
224  if(vocabulary_->load(filePath))
225  {
226  if(objects_.size())
227  {
229  }
230  return true;
231  }
232  }
233  return false;
234 }
235 
236 int FindObject::loadObjects(const QString & dirPath, bool recursive)
237 {
238  QString formats = Settings::getGeneral_imageFormats().remove('*').remove('.');
239 
240  QStringList paths;
241  paths.append(dirPath);
242 
243  QList<int> idsLoaded;
244  while(paths.size())
245  {
246  QString currentDir = paths.front();
247  UDirectory dir(currentDir.toStdString(), formats.toStdString());
248  if(dir.isValid())
249  {
250  const std::list<std::string> & names = dir.getFileNames(); // sorted in natural order
251  for(std::list<std::string>::const_iterator iter=names.begin(); iter!=names.end(); ++iter)
252  {
253  const ObjSignature * s = this->addObject((currentDir.toStdString()+dir.separator()+*iter).c_str());
254  if(s)
255  {
256  idsLoaded.push_back(s->id());
257  }
258  }
259  }
260 
261  paths.pop_front();
262 
263  if(recursive)
264  {
265  QDir d(currentDir);
266  QStringList subDirs = d.entryList(QDir::AllDirs|QDir::NoDotAndDotDot, QDir::Name);
267  for(int i=subDirs.size()-1; i>=0; --i)
268  {
269  paths.prepend(currentDir+QDir::separator()+subDirs[i]);
270  }
271  }
272  }
273 
274  if(idsLoaded.size())
275  {
276  this->updateObjects(idsLoaded);
277  this->updateVocabulary(idsLoaded);
278  }
279 
280  return idsLoaded.size();
281 }
282 
283 const ObjSignature * FindObject::addObject(const QString & filePath)
284 {
285  if(!filePath.isNull())
286  {
287  cv::Mat img = cv::imread(filePath.toStdString().c_str(), cv::IMREAD_GRAYSCALE);
288  if(!img.empty())
289  {
290  int id = 0;
291  QFileInfo file(filePath);
292  QStringList list = file.fileName().split('.');
293  if(list.size())
294  {
295  bool ok = false;
296  id = list.front().toInt(&ok);
297  if(ok && id>0)
298  {
299  if(objects_.contains(id))
300  {
301  UWARN("Object %d already added, a new ID will be generated (new id=%d).", id, Settings::getGeneral_nextObjID());
302  id = 0;
303  }
304  }
305  else
306  {
307  id = 0;
308  }
309  }
310  else
311  {
312  UERROR("File name doesn't contain \".\" (\"%s\")", filePath.toStdString().c_str());
313  }
314 
315  const ObjSignature * s = this->addObject(img, id, filePath);
316  if(s)
317  {
318  UINFO("Added object %d (%s)", s->id(), filePath.toStdString().c_str());
319  return s;
320  }
321  }
322  else
323  {
324  UERROR("Could not read image \"%s\"", filePath.toStdString().c_str());
325  }
326  }
327  else
328  {
329  UERROR("File path is null!?");
330  }
331  return 0;
332 }
333 
334 const ObjSignature * FindObject::addObject(const cv::Mat & image, int id, const QString & filePath)
335 {
336  UASSERT(id >= 0);
337  ObjSignature * s = new ObjSignature(id, image, filePath);
338  if(!this->addObject(s))
339  {
340  delete s;
341  return 0;
342  }
343  return s;
344 }
345 
347 {
348  UASSERT(obj != 0 && obj->id() >= 0);
349  if(obj->id() && objects_.contains(obj->id()))
350  {
351  UERROR("object with id %d already added!", obj->id());
352  return false;
353  }
354  else if(obj->id() == 0)
355  {
356  obj->setId(Settings::getGeneral_nextObjID());
357  }
358 
359  Settings::setGeneral_nextObjID(obj->id()+1);
360 
361  objects_.insert(obj->id(), obj);
362 
363  return true;
364 }
365 
367 {
368  if(objects_.contains(id))
369  {
370  delete objects_.value(id);
371  objects_.remove(id);
372  clearVocabulary();
373  }
374 }
375 
377 {
378  qDeleteAll(objects_);
379  objects_.clear();
380  clearVocabulary();
381 }
382 
383 void FindObject::addObjectAndUpdate(const cv::Mat & image, int id, const QString & filePath)
384 {
385  const ObjSignature * s = this->addObject(image, id, filePath);
386  if(s)
387  {
388  QList<int> ids;
389  ids.push_back(s->id());
390  updateObjects(ids);
391  updateVocabulary(ids);
392  }
393 }
394 
396 {
397  if(objects_.contains(id))
398  {
399  delete objects_.value(id);
400  objects_.remove(id);
401  }
403 }
404 
406 {
407  delete detector_;
408  delete extractor_;
411  UASSERT(detector_ != 0 && extractor_ != 0);
412 }
413 
414 std::vector<cv::KeyPoint> limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, int maxKeypoints)
415 {
416  std::vector<cv::KeyPoint> kptsKept;
417  if(maxKeypoints > 0 && (int)keypoints.size() > maxKeypoints)
418  {
419  // Sort words by response
420  std::multimap<float, int> reponseMap; // <response,id>
421  for(unsigned int i = 0; i <keypoints.size(); ++i)
422  {
423  //Keep track of the data, to be easier to manage the data in the next step
424  reponseMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
425  }
426 
427  // Remove them
428  std::multimap<float, int>::reverse_iterator iter = reponseMap.rbegin();
429  kptsKept.resize(maxKeypoints);
430  for(unsigned int k=0; k < kptsKept.size() && iter!=reponseMap.rend(); ++k, ++iter)
431  {
432  kptsKept[k] = keypoints[iter->second];
433  }
434  }
435  else
436  {
437  kptsKept = keypoints;
438  }
439  return kptsKept;
440 }
441 
442 void limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints)
443 {
444  UASSERT((int)keypoints.size() == descriptors.rows);
445  std::vector<cv::KeyPoint> kptsKept;
446  cv::Mat descriptorsKept;
447  if(maxKeypoints > 0 && (int)keypoints.size() > maxKeypoints)
448  {
449  descriptorsKept = cv::Mat(0, descriptors.cols, descriptors.type());
450 
451  // Sort words by response
452  std::multimap<float, int> reponseMap; // <response,id>
453  for(unsigned int i = 0; i <keypoints.size(); ++i)
454  {
455  //Keep track of the data, to be easier to manage the data in the next step
456  reponseMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
457  }
458 
459  // Remove them
460  std::multimap<float, int>::reverse_iterator iter = reponseMap.rbegin();
461  kptsKept.resize(maxKeypoints);
462  descriptorsKept.reserve(maxKeypoints);
463  for(unsigned int k=0; k < kptsKept.size() && iter!=reponseMap.rend(); ++k, ++iter)
464  {
465  kptsKept[k] = keypoints[iter->second];
466  descriptorsKept.push_back(descriptors.row(iter->second));
467  }
468  }
469  keypoints = kptsKept;
470  descriptors = descriptorsKept;
471  UASSERT_MSG((int)keypoints.size() == descriptors.rows, uFormat("%d vs %d", (int)keypoints.size(), descriptors.rows).c_str());
472 }
473 
475  Feature2D * detector,
476  Feature2D * extractor,
477  const cv::Mat & image,
478  const cv::Mat & mask,
479  std::vector<cv::KeyPoint> & keypoints,
480  cv::Mat & descriptors,
481  int & timeDetection,
482  int & timeExtraction)
483 {
484  QTime timeStep;
485  timeStep.start();
486  keypoints.clear();
487  descriptors = cv::Mat();
488 
489  int maxFeatures = Settings::getFeature2D_3MaxFeatures();
491  {
492  detector->detectAndCompute(image, keypoints, descriptors, mask);
493  UASSERT_MSG((int)keypoints.size() == descriptors.rows, uFormat("%d vs %d", (int)keypoints.size(), descriptors.rows).c_str());
494  if(maxFeatures > 0 && (int)keypoints.size() > maxFeatures)
495  {
496  limitKeypoints(keypoints, descriptors, maxFeatures);
497  }
498  timeDetection=timeStep.restart();
499  timeExtraction = 0;
500  }
501  else
502  {
503  detector->detect(image, keypoints, mask);
504  if(maxFeatures > 0 && (int)keypoints.size() > maxFeatures)
505  {
506  keypoints = limitKeypoints(keypoints, maxFeatures);
507  }
508  timeDetection=timeStep.restart();
509 
510  //Extract descriptors
511  try
512  {
513  extractor->compute(image, keypoints, descriptors);
514  UASSERT_MSG((int)keypoints.size() == descriptors.rows, uFormat("%d vs %d", (int)keypoints.size(), descriptors.rows).c_str());
515  }
516  catch(cv::Exception & e)
517  {
518  UERROR("Descriptor exception: %s. Maybe some keypoints are invalid "
519  "for the selected descriptor extractor.", e.what());
520  descriptors = cv::Mat();
521  keypoints.clear();
522  }
523  catch ( const std::exception& e )
524  {
525  // standard exceptions
526  UERROR("Descriptor exception: %s. Maybe some keypoints are invalid "
527  "for the selected descriptor extractor.", e.what());
528  descriptors = cv::Mat();
529  keypoints.clear();
530  }
531  timeExtraction+=timeStep.restart();
532  }
533 
534  if( Settings::getFeature2D_SIFT_rootSIFT() &&
535  Settings::currentDescriptorType() == "SIFT" &&
536  !descriptors.empty())
537  {
538  UINFO("Performing RootSIFT...");
539  // see http://www.pyimagesearch.com/2015/04/13/implementing-rootsift-in-python-and-opencv/
540  // apply the Hellinger kernel by first L1-normalizing and taking the
541  // square-root
542  for(int i=0; i<descriptors.rows; ++i)
543  {
544  descriptors.row(i) = descriptors.row(i) / cv::sum(descriptors.row(i))[0];
545  cv::sqrt(descriptors.row(i), descriptors.row(i));
546 
547  // By taking the L1 norm, followed by the square-root, we have
548  // already L2 normalized the feature vector and further normalization
549  // is not needed.
550  //descs /= (np.linalg.norm(descs, axis=1, ord=2) + eps);
551  }
552  }
553 }
554 
555 
556 // taken from ASIFT example https://github.com/Itseez/opencv/blob/master/samples/python2/asift.py
557 // affine - is an affine transform matrix from skew_img to img
559  float tilt,
560  float phi,
561  const cv::Mat & image,
562  cv::Mat & skewImage,
563  cv::Mat & skewMask,
564  cv::Mat & Ai)
565 {
566  float h = image.rows;
567  float w = image.cols;
568  cv::Mat A = cv::Mat::zeros(2,3,CV_32FC1);
569  A.at<float>(0,0) = A.at<float>(1,1) = 1;
570  skewMask = cv::Mat::ones(h, w, CV_8U) * 255;
571  if(phi != 0.0)
572  {
573  phi = phi*CV_PI/180.0f; // deg2rad
574  float s = std::sin(phi);
575  float c = std::cos(phi);
576  cv::Mat A22 = (cv::Mat_<float>(2, 2) <<
577  c, -s,
578  s, c);
579  cv::Mat cornersIn = (cv::Mat_<float>(4, 2) <<
580  0,0,
581  w,0,
582  w,h,
583  0,h);
584  cv::Mat cornersOut = cornersIn * A22.t();
585  cv::Rect rect = cv::boundingRect(cornersOut.reshape(2,4));
586  A = (cv::Mat_<float>(2, 3) <<
587  c, -s, -rect.x,
588  s, c, -rect.y);
589  cv::warpAffine(image, skewImage, A, cv::Size(rect.width, rect.height), cv::INTER_LINEAR, cv::BORDER_REPLICATE);
590  }
591  else
592  {
593  skewImage = image;
594  }
595  if(tilt != 1.0)
596  {
597  float s = 0.8*std::sqrt(tilt*tilt-1);
598  cv::Mat out, out2;
599  cv::GaussianBlur(skewImage, out, cv::Size(0, 0), s, 0.01);
600  cv::resize(out, out2, cv::Size(0, 0), 1.0/tilt, 1.0, cv::INTER_NEAREST);
601  skewImage = out2;
602  A.row(0) /= tilt;
603  }
604  if(phi != 0.0 || tilt != 1.0)
605  {
606  cv::Mat mask = skewMask;
607  cv::warpAffine(mask, skewMask, A, skewImage.size(), cv::INTER_NEAREST);
608  }
609  cv::invertAffineTransform(A, Ai);
610 }
611 
612 class AffineExtractionThread : public QThread
613 {
614 public:
616  Feature2D * detector,
617  Feature2D * extractor,
618  const cv::Mat & image,
619  float tilt,
620  float phi) :
621  detector_(detector),
622  extractor_(extractor),
623  image_(image),
624  tilt_(tilt),
625  phi_(phi),
626  timeSkewAffine_(0),
627  timeDetection_(0),
628  timeExtraction_(0),
629  timeSubPix_(0)
630  {
631  UASSERT(detector && extractor);
632  }
633  const cv::Mat & image() const {return image_;}
634  const std::vector<cv::KeyPoint> & keypoints() const {return keypoints_;}
635  const cv::Mat & descriptors() const {return descriptors_;}
636 
637  int timeSkewAffine() const {return timeSkewAffine_;}
638  int timeDetection() const {return timeDetection_;}
639  int timeExtraction() const {return timeExtraction_;}
640  int timeSubPix() const {return timeSubPix_;}
641 
642 protected:
643  virtual void run()
644  {
645  QTime timeStep;
646  timeStep.start();
647  cv::Mat skewImage, skewMask, Ai;
648  FindObject::affineSkew(tilt_, phi_, image_, skewImage, skewMask, Ai);
649  timeSkewAffine_=timeStep.restart();
650 
651  //Detect features
653  detector_,
654  extractor_,
655  skewImage,
656  skewMask,
657  keypoints_,
658  descriptors_,
659  timeDetection_,
660  timeExtraction_);
661  timeStep.start();
662 
663  // Transform points to original image coordinates
664  for(unsigned int i=0; i<keypoints_.size(); ++i)
665  {
666  cv::Mat p = (cv::Mat_<float>(3, 1) << keypoints_[i].pt.x, keypoints_[i].pt.y, 1);
667  cv::Mat pa = Ai * p;
668  keypoints_[i].pt.x = pa.at<float>(0,0);
669  keypoints_[i].pt.y = pa.at<float>(1,0);
670  }
671 
672  if(keypoints_.size() && Settings::getFeature2D_6SubPix())
673  {
674  // Sub pixel should be done after descriptors extraction
675  std::vector<cv::Point2f> corners;
676  cv::KeyPoint::convert(keypoints_, corners);
677  cv::cornerSubPix(image_,
678  corners,
679  cv::Size(Settings::getFeature2D_7SubPixWinSize(), Settings::getFeature2D_7SubPixWinSize()),
680  cv::Size(-1,-1),
681  cv::TermCriteria( CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, Settings::getFeature2D_8SubPixIterations(), Settings::getFeature2D_9SubPixEps() ));
682  UASSERT(corners.size() == keypoints_.size());
683  for(unsigned int i=0; i<corners.size(); ++i)
684  {
685  keypoints_[i].pt = corners[i];
686  }
687  timeSubPix_ +=timeStep.restart();
688  }
689  }
690 private:
693  cv::Mat image_;
694  float tilt_;
695  float phi_;
696  std::vector<cv::KeyPoint> keypoints_;
697  cv::Mat descriptors_;
698 
703 };
704 
705 class ExtractFeaturesThread : public QThread
706 {
707 public:
709  Feature2D * detector,
710  Feature2D * extractor,
711  int objectId,
712  const cv::Mat & image) :
713  detector_(detector),
714  extractor_(extractor),
715  objectId_(objectId),
716  image_(image),
717  timeSkewAffine_(0),
718  timeDetection_(0),
719  timeExtraction_(0),
720  timeSubPix_(0)
721  {
722  UASSERT(detector && extractor);
723  UASSERT_MSG(!image.empty() && image.type() == CV_8UC1,
724  uFormat("Image of object %d is null or not type CV_8UC1!?!? (cols=%d, rows=%d, type=%d)",
725  objectId, image.cols, image.rows, image.type()).c_str());
726  }
728  int objectId() const {return objectId_;}
729  const cv::Mat & image() const {return image_;}
730  const std::vector<cv::KeyPoint> & keypoints() const {return keypoints_;}
731  const cv::Mat & descriptors() const {return descriptors_;}
732 
733  int timeSkewAffine() const {return timeSkewAffine_;}
734  int timeDetection() const {return timeDetection_;}
735  int timeExtraction() const {return timeExtraction_;}
736  int timeSubPix() const {return timeSubPix_;}
737 
738 protected:
739  virtual void run()
740  {
741  QTime time;
742  time.start();
743  UDEBUG("Extracting descriptors from object %d...", objectId_);
744 
745  QTime timeStep;
746  timeStep.start();
747 
748  if(!Settings::getFeature2D_4Affine())
749  {
751  detector_,
752  extractor_,
753  image_,
754  cv::Mat(),
755  keypoints_,
756  descriptors_,
757  timeDetection_,
758  timeExtraction_);
759  timeStep.start();
760 
761  if(keypoints_.size())
762  {
763  UDEBUG("Detected %d features from object %d...", (int)keypoints_.size(), objectId_);
764  if(Settings::getFeature2D_6SubPix())
765  {
766  // Sub pixel should be done after descriptors extraction
767  std::vector<cv::Point2f> corners;
768  cv::KeyPoint::convert(keypoints_, corners);
769  cv::cornerSubPix(image_,
770  corners,
771  cv::Size(Settings::getFeature2D_7SubPixWinSize(), Settings::getFeature2D_7SubPixWinSize()),
772  cv::Size(-1,-1),
773  cv::TermCriteria( CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, Settings::getFeature2D_8SubPixIterations(), Settings::getFeature2D_9SubPixEps() ));
774  UASSERT(corners.size() == keypoints_.size());
775  for(unsigned int i=0; i<corners.size(); ++i)
776  {
777  keypoints_[i].pt = corners[i];
778  }
779  timeSubPix_ +=timeStep.restart();
780  }
781  }
782  else
783  {
784  UWARN("no features detected in object %d !?!", objectId_);
785  }
786  }
787  else
788  {
789  //ASIFT
790  std::vector<float> tilts;
791  std::vector<float> phis;
792  tilts.push_back(1.0f);
793  phis.push_back(0.0f);
794  int nTilt = Settings::getFeature2D_5AffineCount();
795  for(int t=1; t<nTilt; ++t)
796  {
797  float tilt = std::pow(2.0f, 0.5f*float(t));
798  float inc = 72.0f / float(tilt);
799  for(float phi=0.0f; phi<180.0f; phi+=inc)
800  {
801  tilts.push_back(tilt);
802  phis.push_back(phi);
803  }
804  }
805 
806  //multi-threaded
807  unsigned int threadCounts = Settings::getGeneral_threads();
808  if(threadCounts == 0)
809  {
810  threadCounts = (unsigned int)tilts.size();
811  }
812 
813  for(unsigned int i=0; i<tilts.size(); i+=threadCounts)
814  {
815  QVector<AffineExtractionThread*> threads;
816 
817  for(unsigned int k=i; k<i+threadCounts && k<tilts.size(); ++k)
818  {
819  threads.push_back(new AffineExtractionThread(detector_, extractor_, image_, tilts[k], phis[k]));
820  threads.back()->start();
821  }
822 
823  for(int k=0; k<threads.size(); ++k)
824  {
825  threads[k]->wait();
826 
827  keypoints_.insert(keypoints_.end(), threads[k]->keypoints().begin(), threads[k]->keypoints().end());
828  descriptors_.push_back(threads[k]->descriptors());
829 
830  timeSkewAffine_ += threads[k]->timeSkewAffine();
831  timeDetection_ += threads[k]->timeDetection();
832  timeExtraction_ += threads[k]->timeExtraction();
833  timeSubPix_ += threads[k]->timeSubPix();
834 
835  delete threads[k];
836  }
837  }
838  }
839 
840  UINFO("%d descriptors extracted from object %d (in %d ms)", descriptors_.rows, objectId_, time.elapsed());
841  }
842 private:
846  cv::Mat image_;
847  std::vector<cv::KeyPoint> keypoints_;
848  cv::Mat descriptors_;
849 
854 };
855 
856 void FindObject::updateObjects(const QList<int> & ids)
857 {
858  UINFO("Update %d objects...", ids.size());
859  QList<ObjSignature*> objectsList;
860  if(ids.size())
861  {
862  for(int i=0; i<ids.size(); ++i)
863  {
864  if(objects_.contains(ids[i]))
865  {
866  objectsList.push_back(objects_[ids[i]]);
867  }
868  else
869  {
870  UERROR("Not found object %d!", ids[i]);
871  }
872  }
873  }
874  else
875  {
876  objectsList = objects_.values();
877  }
878 
879  if(objectsList.size())
880  {
881  sessionModified_ = true;
882  int threadCounts = Settings::getGeneral_threads();
883  if(threadCounts == 0)
884  {
885  threadCounts = objectsList.size();
886  }
887 
888  QTime time;
889  time.start();
890 
891  if(objectsList.size())
892  {
893  UINFO("Features extraction from %d objects... (threads=%d)", objectsList.size(), threadCounts);
894  for(int i=0; i<objectsList.size(); i+=threadCounts)
895  {
896  QVector<ExtractFeaturesThread*> threads;
897  for(int k=i; k<i+threadCounts && k<objectsList.size(); ++k)
898  {
899  if(!objectsList.at(k)->image().empty())
900  {
901  threads.push_back(new ExtractFeaturesThread(detector_, extractor_, objectsList.at(k)->id(), objectsList.at(k)->image()));
902  threads.back()->start();
903  }
904  else
905  {
906  objects_.value(objectsList.at(k)->id())->setData(std::vector<cv::KeyPoint>(), cv::Mat());
907  if(keepImagesInRAM_)
908  {
909  UERROR("Empty image detected for object %d!? No features can be detected.", objectsList.at(k)->id());
910 
911  }
912  else
913  {
914  UWARN("Empty image detected for object %d! No features can be detected. Note that images are in not kept in RAM.", objectsList.at(k)->id());
915  }
916  }
917  }
918 
919  for(int j=0; j<threads.size(); ++j)
920  {
921  threads[j]->wait();
922 
923  int id = threads[j]->objectId();
924 
925  objects_.value(id)->setData(threads[j]->keypoints(), threads[j]->descriptors());
926 
927  if(!keepImagesInRAM_)
928  {
929  objects_.value(id)->removeImage();
930  }
931  delete threads[j];
932  }
933  }
934  UINFO("Features extraction from %d objects... done! (%d ms)", objectsList.size(), time.elapsed());
935  }
936  }
937  else
938  {
939  UINFO("No objects to update...");
940  }
941 }
942 
944 {
945  objectsDescriptors_.clear();
946  dataRange_.clear();
947  vocabulary_->clear();
948 }
949 
950 void FindObject::updateVocabulary(const QList<int> & ids)
951 {
952  int count = 0;
953  int dim = -1;
954  int type = -1;
955  QList<ObjSignature*> objectsList;
956  if(ids.size())
957  {
958  for(int i=0; i<ids.size(); ++i)
959  {
960  if(objects_.contains(ids[i]))
961  {
962  objectsList.push_back(objects_[ids[i]]);
963  }
964  else
965  {
966  UERROR("Not found object %d!", ids[i]);
967  }
968  }
969  if(vocabulary_->size())
970  {
971  dim = vocabulary_->dim();
972  type = vocabulary_->type();
973  }
974  }
975  else
976  {
977  clearVocabulary();
978  objectsList = objects_.values();
979  }
980 
981  // Get the total size and verify descriptors
982  for(int i=0; i<objectsList.size(); ++i)
983  {
984  if(!objectsList.at(i)->descriptors().empty())
985  {
986  if(dim >= 0 && objectsList.at(i)->descriptors().cols != dim)
987  {
988  UERROR("Descriptors of the objects are not all the same size! Objects "
989  "opened must have all the same size (and from the same descriptor extractor).");
990  return;
991  }
992  dim = objectsList.at(i)->descriptors().cols;
993  if(type >= 0 && objectsList.at(i)->descriptors().type() != type)
994  {
995  UERROR("Descriptors of the objects are not all the same type! Objects opened "
996  "must have been processed by the same descriptor extractor.");
997  return;
998  }
999  type = objectsList.at(i)->descriptors().type();
1000  count += objectsList.at(i)->descriptors().rows;
1001  }
1002  }
1003 
1004  UINFO("Updating vocabulary with %d objects and %d descriptors...", ids.size(), count);
1005 
1006  // Copy data
1007  if(count)
1008  {
1009  UINFO("Updating global descriptors matrix: Objects=%d, total descriptors=%d, dim=%d, type=%d",
1010  (int)objects_.size(), count, dim, type);
1011  if(!Settings::getGeneral_invertedSearch())
1012  {
1013  if(Settings::getGeneral_threads() == 1)
1014  {
1015  // If only one thread, put all descriptors in the same cv::Mat
1016  int row = 0;
1017  bool vocabularyEmpty = objectsDescriptors_.size() == 0;
1018  if(vocabularyEmpty)
1019  {
1020  UASSERT(objectsDescriptors_.size() == 0);
1021  objectsDescriptors_.insert(0, cv::Mat(count, dim, type));
1022  }
1023  else
1024  {
1025  row = objectsDescriptors_.begin().value().rows;
1026  }
1027  for(int i=0; i<objectsList.size(); ++i)
1028  {
1029  objectsList[i]->setWords(QMultiMap<int,int>());
1030  if(objectsList.at(i)->descriptors().rows)
1031  {
1032  if(vocabularyEmpty)
1033  {
1034  cv::Mat dest(objectsDescriptors_.begin().value(), cv::Range(row, row+objectsList.at(i)->descriptors().rows));
1035  objectsList.at(i)->descriptors().copyTo(dest);
1036  }
1037  else
1038  {
1039  UASSERT_MSG(objectsDescriptors_.begin().value().cols == objectsList.at(i)->descriptors().cols,
1040  uFormat("%d vs %d", objectsDescriptors_.begin().value().cols, objectsList.at(i)->descriptors().cols).c_str());
1041  UASSERT(objectsDescriptors_.begin().value().type() == objectsList.at(i)->descriptors().type());
1042  objectsDescriptors_.begin().value().push_back(objectsList.at(i)->descriptors());
1043  }
1044 
1045  row += objectsList.at(i)->descriptors().rows;
1046  // dataRange contains the upper_bound for each
1047  // object (the last descriptors position in the
1048  // global object descriptors matrix)
1049  if(objectsList.at(i)->descriptors().rows)
1050  {
1051  dataRange_.insert(row-1, objectsList.at(i)->id());
1052  }
1053  }
1054  }
1055  }
1056  else
1057  {
1058  for(int i=0; i<objectsList.size(); ++i)
1059  {
1060  objectsList[i]->setWords(QMultiMap<int,int>());
1061  objectsDescriptors_.insert(objectsList.at(i)->id(), objectsList.at(i)->descriptors());
1062  }
1063  }
1064  }
1065  else
1066  {
1067  // Inverted index on (vocabulary)
1068  sessionModified_ = true;
1069  QTime time;
1070  time.start();
1071  bool incremental = Settings::getGeneral_vocabularyIncremental() && !Settings::getGeneral_vocabularyFixed();
1072  if(incremental)
1073  {
1074  UINFO("Creating incremental vocabulary...");
1075  }
1076  else if(Settings::getGeneral_vocabularyFixed())
1077  {
1078  UINFO("Updating vocabulary correspondences only (vocabulary is fixed)...");
1079  }
1080  else
1081  {
1082  UINFO("Creating vocabulary...");
1083  }
1084  QTime localTime;
1085  localTime.start();
1086  int updateVocabularyMinWords = Settings::getGeneral_vocabularyUpdateMinWords();
1087  int addedWords = 0;
1088  for(int i=0; i<objectsList.size(); ++i)
1089  {
1090  UASSERT(objectsList[i]->descriptors().rows == (int)objectsList[i]->keypoints().size());
1091  QMultiMap<int, int> words = vocabulary_->addWords(objectsList[i]->descriptors(), objectsList.at(i)->id());
1092  objectsList[i]->setWords(words);
1093  addedWords += words.uniqueKeys().size();
1094  bool updated = false;
1095  if(incremental && addedWords && addedWords >= updateVocabularyMinWords)
1096  {
1097  vocabulary_->update();
1098  addedWords = 0;
1099  updated = true;
1100  }
1101  UINFO("Object %d, %d words from %d descriptors (%d words, %d ms) %s",
1102  objectsList[i]->id(),
1103  words.uniqueKeys().size(),
1104  objectsList[i]->descriptors().rows,
1105  vocabulary_->size(),
1106  localTime.restart(),
1107  updated?"updated":"");
1108  }
1109  if(addedWords && !Settings::getGeneral_vocabularyFixed())
1110  {
1111  if(!incremental)
1112  {
1113  UINFO("Updating vocabulary...");
1114  }
1115  vocabulary_->update();
1116  }
1117 
1118  if(incremental)
1119  {
1120  UINFO("Creating incremental vocabulary... done! size=%d (%d ms)", vocabulary_->size(), time.elapsed());
1121  }
1122  else if(Settings::getGeneral_vocabularyFixed())
1123  {
1124  UINFO("Updating vocabulary correspondences only (vocabulary is fixed)... done! size=%d (%d ms)", vocabulary_->size(), time.elapsed());
1125  }
1126  else
1127  {
1128  UINFO("Creating vocabulary... done! size=%d (%d ms)", vocabulary_->size(), time.elapsed());
1129  }
1130  }
1131  }
1132 }
1133 
1134 class SearchThread: public QThread
1135 {
1136 public:
1137  SearchThread(Vocabulary * vocabulary, int objectId, const cv::Mat * descriptors, const QMultiMap<int, int> * sceneWords) :
1138  vocabulary_(vocabulary),
1139  objectId_(objectId),
1140  descriptors_(descriptors),
1141  sceneWords_(sceneWords),
1142  minMatchedDistance_(-1.0f),
1143  maxMatchedDistance_(-1.0f)
1144  {
1145  UASSERT(descriptors);
1146  }
1147  virtual ~SearchThread() {}
1148 
1149  int getObjectId() const {return objectId_;}
1150  float getMinMatchedDistance() const {return minMatchedDistance_;}
1151  float getMaxMatchedDistance() const {return maxMatchedDistance_;}
1152  const QMultiMap<int, int> & getMatches() const {return matches_;}
1153 
1154 protected:
1155  virtual void run()
1156  {
1157  //QTime time;
1158  //time.start();
1159 
1160  cv::Mat results;
1161  cv::Mat dists;
1162 
1163  //match objects to scene
1164  int k = Settings::getNearestNeighbor_3nndrRatioUsed()?2:1;
1165  results = cv::Mat(descriptors_->rows, k, CV_32SC1); // results index
1166  dists = cv::Mat(descriptors_->rows, k, CV_32FC1); // Distance results are CV_32FC1
1167  vocabulary_->search(*descriptors_, results, dists, k);
1168 
1169  // PROCESS RESULTS
1170  // Get all matches for each object
1171  for(int i=0; i<dists.rows; ++i)
1172  {
1173  // Check if this descriptor matches with those of the objects
1174  bool matched = false;
1175 
1176  if(Settings::getNearestNeighbor_3nndrRatioUsed() &&
1177  dists.at<float>(i,0) <= Settings::getNearestNeighbor_4nndrRatio() * dists.at<float>(i,1))
1178  {
1179  matched = true;
1180  }
1181  if((matched || !Settings::getNearestNeighbor_3nndrRatioUsed()) &&
1182  Settings::getNearestNeighbor_5minDistanceUsed())
1183  {
1184  if(dists.at<float>(i,0) <= Settings::getNearestNeighbor_6minDistance())
1185  {
1186  matched = true;
1187  }
1188  else
1189  {
1190  matched = false;
1191  }
1192  }
1193  if(!matched && !Settings::getNearestNeighbor_3nndrRatioUsed() && !Settings::getNearestNeighbor_5minDistanceUsed())
1194  {
1195  matched = true; // no criterion, match to the nearest descriptor
1196  }
1197  if(minMatchedDistance_ == -1 || minMatchedDistance_ > dists.at<float>(i,0))
1198  {
1199  minMatchedDistance_ = dists.at<float>(i,0);
1200  }
1201  if(maxMatchedDistance_ == -1 || maxMatchedDistance_ < dists.at<float>(i,0))
1202  {
1203  maxMatchedDistance_ = dists.at<float>(i,0);
1204  }
1205 
1206  int wordId = results.at<int>(i,0);
1207  if(matched && sceneWords_->count(wordId) == 1)
1208  {
1209  matches_.insert(i, sceneWords_->value(wordId));
1210  matches_.insert(i, results.at<int>(i,0));
1211  }
1212  }
1213 
1214  //UINFO("Search Object %d time=%d ms", objectIndex_, time.elapsed());
1215  }
1216 private:
1217  Vocabulary * vocabulary_; // would be const but flann search() method is not const!?
1219  const cv::Mat * descriptors_;
1220  const QMultiMap<int, int> * sceneWords_; // <word id, keypoint indexes>
1221 
1224  QMultiMap<int, int> matches_;
1225 };
1226 
1227 class HomographyThread: public QThread
1228 {
1229 public:
1231  const QMultiMap<int, int> * matches, // <object, scene>
1232  int objectId,
1233  const std::vector<cv::KeyPoint> * kptsA,
1234  const std::vector<cv::KeyPoint> * kptsB,
1235  const cv::Mat & imageA, // image only required if opticalFlow is on
1236  const cv::Mat & imageB) : // image only required if opticalFlow is on
1237  matches_(matches),
1238  objectId_(objectId),
1239  kptsA_(kptsA),
1240  kptsB_(kptsB),
1241  imageA_(imageA),
1242  imageB_(imageB),
1243  code_(DetectionInfo::kRejectedUndef)
1244  {
1245  UASSERT(matches && kptsA && kptsB);
1246  }
1247  virtual ~HomographyThread() {}
1248 
1249  int getObjectId() const {return objectId_;}
1250  const std::vector<int> & getIndexesA() const {return indexesA_;}
1251  const std::vector<int> & getIndexesB() const {return indexesB_;}
1252  const std::vector<uchar> & getOutlierMask() const {return outlierMask_;}
1253  QMultiMap<int, int> getInliers() const {return inliers_;}
1254  QMultiMap<int, int> getOutliers() const {return outliers_;}
1255  const cv::Mat & getHomography() const {return h_;}
1257 
1258 protected:
1259  virtual void run()
1260  {
1261  //QTime time;
1262  //time.start();
1263 
1264  std::vector<cv::Point2f> mpts_1(matches_->size());
1265  std::vector<cv::Point2f> mpts_2(matches_->size());
1266  indexesA_.resize(matches_->size());
1267  indexesB_.resize(matches_->size());
1268 
1269  UDEBUG("Fill matches...");
1270  int j=0;
1271  for(QMultiMap<int, int>::const_iterator iter = matches_->begin(); iter!=matches_->end(); ++iter)
1272  {
1273  UASSERT_MSG(iter.key() < (int)kptsA_->size(), uFormat("key=%d size=%d", iter.key(),(int)kptsA_->size()).c_str());
1274  UASSERT_MSG(iter.value() < (int)kptsB_->size(), uFormat("key=%d size=%d", iter.value(),(int)kptsB_->size()).c_str());
1275  mpts_1[j] = kptsA_->at(iter.key()).pt;
1276  indexesA_[j] = iter.key();
1277  mpts_2[j] = kptsB_->at(iter.value()).pt;
1278  indexesB_[j] = iter.value();
1279  ++j;
1280  }
1281 
1282  if((int)mpts_1.size() >= Settings::getHomography_minimumInliers())
1283  {
1284  if(Settings::getHomography_opticalFlow())
1285  {
1286  UASSERT(!imageA_.empty() && !imageB_.empty());
1287 
1288  cv::Mat imageA = imageA_;
1289  cv::Mat imageB = imageB_;
1290  if(imageA_.cols < imageB_.cols && imageA_.rows < imageB_.rows)
1291  {
1292  // padding, optical flow wants images of the same size
1293  imageA = cv::Mat::zeros(imageB_.size(), imageA_.type());
1294  imageA_.copyTo(imageA(cv::Rect(0,0,imageA_.cols, imageA_.rows)));
1295  }
1296  if(imageA.size() == imageB.size())
1297  {
1298  UDEBUG("Optical flow...");
1299  //refine matches
1300  std::vector<unsigned char> status;
1301  std::vector<float> err;
1302  cv::calcOpticalFlowPyrLK(
1303  imageA,
1304  imageB_,
1305  mpts_1,
1306  mpts_2,
1307  status,
1308  err,
1309  cv::Size(Settings::getHomography_opticalFlowWinSize(), Settings::getHomography_opticalFlowWinSize()),
1310  Settings::getHomography_opticalFlowMaxLevel(),
1311  cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, Settings::getHomography_opticalFlowIterations(), Settings::getHomography_opticalFlowEps()),
1312  cv::OPTFLOW_LK_GET_MIN_EIGENVALS | cv::OPTFLOW_USE_INITIAL_FLOW, 1e-4);
1313  }
1314  else
1315  {
1316  UERROR("Object's image should be less/equal size of the scene image to use Optical Flow.");
1317  }
1318  }
1319 
1320  UDEBUG("Find homography... begin");
1321 #if CV_MAJOR_VERSION < 3
1322  h_ = findHomography(mpts_1,
1323  mpts_2,
1325  Settings::getHomography_ransacReprojThr(),
1326  outlierMask_);
1327 #else
1328  h_ = findHomography(mpts_1,
1329  mpts_2,
1331  Settings::getHomography_ransacReprojThr(),
1332  outlierMask_,
1333  Settings::getHomography_maxIterations(),
1334  Settings::getHomography_confidence());
1335 #endif
1336  UDEBUG("Find homography... end");
1337 
1338  UASSERT(outlierMask_.size() == 0 || outlierMask_.size() == mpts_1.size());
1339  for(unsigned int k=0; k<mpts_1.size();++k)
1340  {
1341  if(outlierMask_.size() && outlierMask_.at(k))
1342  {
1343  inliers_.insert(indexesA_[k], indexesB_[k]);
1344  }
1345  else
1346  {
1347  outliers_.insert(indexesA_[k], indexesB_[k]);
1348  }
1349  }
1350 
1351  if(inliers_.size() == (int)outlierMask_.size() && !h_.empty())
1352  {
1353  if(Settings::getHomography_ignoreWhenAllInliers() || cv::countNonZero(h_) < 1)
1354  {
1355  // ignore homography when all features are inliers
1356  h_ = cv::Mat();
1358  }
1359  }
1360  }
1361  else
1362  {
1364  }
1365 
1366  //UINFO("Homography Object %d time=%d ms", objectIndex_, time.elapsed());
1367  }
1368 private:
1369  const QMultiMap<int, int> * matches_;
1371  const std::vector<cv::KeyPoint> * kptsA_;
1372  const std::vector<cv::KeyPoint> * kptsB_;
1373  cv::Mat imageA_;
1374  cv::Mat imageB_;
1376 
1377  std::vector<int> indexesA_;
1378  std::vector<int> indexesB_;
1379  std::vector<uchar> outlierMask_;
1380  QMultiMap<int, int> inliers_;
1381  QMultiMap<int, int> outliers_;
1382  cv::Mat h_;
1383 };
1384 
1385 void FindObject::detect(const cv::Mat & image)
1386 {
1387  detect(image, Header(), cv::Mat(), 0.0);
1388 }
1389 
1390 void FindObject::detect(const cv::Mat & image, const Header & header, const cv::Mat & depth, float depthConstant)
1391 {
1392  QTime time;
1393  time.start();
1394  DetectionInfo info;
1395  this->detect(image, info);
1396 
1397  if(info.objDetected_.size() > 1)
1398  {
1399  UINFO("(%s) %d objects detected! (%d ms)",
1400  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
1401  (int)info.objDetected_.size(),
1402  time.elapsed());
1403  }
1404  else if(info.objDetected_.size() == 1)
1405  {
1406  UINFO("(%s) Object %d detected! (%d ms)",
1407  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
1408  (int)info.objDetected_.begin().key(),
1409  time.elapsed());
1410  }
1411  else if(Settings::getGeneral_sendNoObjDetectedEvents())
1412  {
1413  UINFO("(%s) No objects detected. (%d ms)",
1414  QTime::currentTime().toString("HH:mm:ss.zzz").toStdString().c_str(),
1415  time.elapsed());
1416  }
1417 
1418  if(info.objDetected_.size() > 0 || Settings::getGeneral_sendNoObjDetectedEvents())
1419  {
1420  Q_EMIT objectsFound(info, header, depth, depthConstant);
1421  }
1422 }
1423 
1424 bool FindObject::detect(const cv::Mat & image, find_object::DetectionInfo & info) const
1425 {
1426  QTime totalTime;
1427  totalTime.start();
1428 
1429  // reset statistics
1430  info = DetectionInfo();
1431 
1432  bool success = false;
1433  if(!image.empty())
1434  {
1435  //Convert to grayscale
1436  cv::Mat grayscaleImg;
1437  if(image.channels() != 1 || image.depth() != CV_8U)
1438  {
1439  cv::cvtColor(image, grayscaleImg, cv::COLOR_BGR2GRAY);
1440  }
1441  else
1442  {
1443  grayscaleImg = image;
1444  }
1445 
1446  // DETECT FEATURES AND EXTRACT DESCRIPTORS
1447  UDEBUG("DETECT FEATURES AND EXTRACT DESCRIPTORS FROM THE SCENE");
1448  ExtractFeaturesThread extractThread(detector_, extractor_, -1, grayscaleImg);
1449  extractThread.start();
1450  extractThread.wait();
1451  info.sceneKeypoints_ = extractThread.keypoints();
1452  info.sceneDescriptors_ = extractThread.descriptors();
1453  UASSERT_MSG((int)extractThread.keypoints().size() == extractThread.descriptors().rows, uFormat("%d vs %d", (int)extractThread.keypoints().size(), extractThread.descriptors().rows).c_str());
1454  info.timeStamps_.insert(DetectionInfo::kTimeKeypointDetection, extractThread.timeDetection());
1456  info.timeStamps_.insert(DetectionInfo::kTimeSubPixelRefining, extractThread.timeSubPix());
1457  info.timeStamps_.insert(DetectionInfo::kTimeSkewAffine, extractThread.timeSkewAffine());
1458 
1459  bool consistentNNData = (vocabulary_->size()!=0 && vocabulary_->wordToObjects().begin().value()!=-1 && Settings::getGeneral_invertedSearch()) ||
1460  ((vocabulary_->size()==0 || vocabulary_->wordToObjects().begin().value()==-1) && !Settings::getGeneral_invertedSearch());
1461 
1462  bool descriptorsValid = !Settings::getGeneral_invertedSearch() &&
1463  !objectsDescriptors_.empty() &&
1464  objectsDescriptors_.begin().value().cols == info.sceneDescriptors_.cols &&
1465  objectsDescriptors_.begin().value().type() == info.sceneDescriptors_.type();
1466 
1467  bool vocabularyValid = Settings::getGeneral_invertedSearch() &&
1468  vocabulary_->size() &&
1469  !vocabulary_->indexedDescriptors().empty() &&
1470  vocabulary_->indexedDescriptors().cols == info.sceneDescriptors_.cols &&
1471  (vocabulary_->indexedDescriptors().type() == info.sceneDescriptors_.type() ||
1472  (Settings::getNearestNeighbor_7ConvertBinToFloat() && vocabulary_->indexedDescriptors().type() == CV_32FC1));
1473 
1474  // COMPARE
1475  UDEBUG("COMPARE");
1476  if((descriptorsValid || vocabularyValid) &&
1477  info.sceneKeypoints_.size() &&
1478  consistentNNData)
1479  {
1480  success = true;
1481  QTime time;
1482  time.start();
1483 
1484  QMultiMap<int, int> words;
1485 
1486  if(!Settings::getGeneral_invertedSearch())
1487  {
1488  vocabulary_->clear();
1489  // CREATE INDEX for the scene
1490  UDEBUG("CREATE INDEX FOR THE SCENE");
1491  words = vocabulary_->addWords(info.sceneDescriptors_, -1);
1492  vocabulary_->update();
1493  info.timeStamps_.insert(DetectionInfo::kTimeIndexing, time.restart());
1494  info.sceneWords_ = words;
1495  }
1496 
1497  for(QMap<int, ObjSignature*>::const_iterator iter=objects_.begin(); iter!=objects_.end(); ++iter)
1498  {
1499  info.matches_.insert(iter.key(), QMultiMap<int, int>());
1500  }
1501 
1502  if(Settings::getGeneral_invertedSearch() || Settings::getGeneral_threads() == 1)
1503  {
1504  cv::Mat results;
1505  cv::Mat dists;
1506  // DO NEAREST NEIGHBOR
1507  UDEBUG("DO NEAREST NEIGHBOR");
1508  int k = Settings::getNearestNeighbor_3nndrRatioUsed()?2:1;
1509  if(!Settings::getGeneral_invertedSearch())
1510  {
1511  //match objects to scene
1512  results = cv::Mat(objectsDescriptors_.begin().value().rows, k, CV_32SC1); // results index
1513  dists = cv::Mat(objectsDescriptors_.begin().value().rows, k, CV_32FC1); // Distance results are CV_32FC1
1514  vocabulary_->search(objectsDescriptors_.begin().value(), results, dists, k);
1515  }
1516  else
1517  {
1518  //match scene to objects
1519  results = cv::Mat(info.sceneDescriptors_.rows, k, CV_32SC1); // results index
1520  dists = cv::Mat(info.sceneDescriptors_.rows, k, CV_32FC1); // Distance results are CV_32FC1
1521  vocabulary_->search(info.sceneDescriptors_, results, dists, k);
1522  }
1523 
1524  // PROCESS RESULTS
1525  UDEBUG("PROCESS RESULTS");
1526  // Get all matches for each object
1527  for(int i=0; i<dists.rows; ++i)
1528  {
1529  // Check if this descriptor matches with those of the objects
1530  bool matched = false;
1531 
1532  if(Settings::getNearestNeighbor_3nndrRatioUsed() &&
1533  dists.at<float>(i,0) <= Settings::getNearestNeighbor_4nndrRatio() * dists.at<float>(i,1))
1534  {
1535  matched = true;
1536  }
1537  if((matched || !Settings::getNearestNeighbor_3nndrRatioUsed()) &&
1538  Settings::getNearestNeighbor_5minDistanceUsed())
1539  {
1540  if(dists.at<float>(i,0) <= Settings::getNearestNeighbor_6minDistance())
1541  {
1542  matched = true;
1543  }
1544  else
1545  {
1546  matched = false;
1547  }
1548  }
1549  if(!matched &&
1550  !Settings::getNearestNeighbor_3nndrRatioUsed() &&
1551  !Settings::getNearestNeighbor_5minDistanceUsed() &&
1552  dists.at<float>(i,0) >= 0.0f)
1553  {
1554  matched = true; // no criterion, match to the nearest descriptor
1555  }
1556  if(info.minMatchedDistance_ == -1 || info.minMatchedDistance_ > dists.at<float>(i,0))
1557  {
1558  info.minMatchedDistance_ = dists.at<float>(i,0);
1559  }
1560  if(info.maxMatchedDistance_ == -1 || info.maxMatchedDistance_ < dists.at<float>(i,0))
1561  {
1562  info.maxMatchedDistance_ = dists.at<float>(i,0);
1563  }
1564 
1565  if(matched)
1566  {
1567  int wordId = results.at<int>(i,0);
1568  if(Settings::getGeneral_invertedSearch())
1569  {
1570  info.sceneWords_.insertMulti(wordId, i);
1571  QList<int> objIds = vocabulary_->wordToObjects().values(wordId);
1572  for(int j=0; j<objIds.size(); ++j)
1573  {
1574  // just add unique matches
1575  if(vocabulary_->wordToObjects().count(wordId, objIds[j]) == 1)
1576  {
1577  info.matches_.find(objIds[j]).value().insert(objects_.value(objIds[j])->words().value(wordId), i);
1578  }
1579  }
1580  }
1581  else
1582  {
1583  QMap<int, int>::const_iterator iter = dataRange_.lowerBound(i);
1584  int objectId = iter.value();
1585  int fisrtObjectDescriptorIndex = (iter == dataRange_.begin())?0:(--iter).key()+1;
1586  int objectDescriptorIndex = i - fisrtObjectDescriptorIndex;
1587 
1588  if(words.count(wordId) == 1)
1589  {
1590  info.matches_.find(objectId).value().insert(objectDescriptorIndex, words.value(wordId));
1591  }
1592  }
1593  }
1594  }
1595  }
1596  else
1597  {
1598  //multi-threaded, match objects to scene
1599  UDEBUG("MULTI-THREADED, MATCH OBJECTS TO SCENE");
1600  int threadCounts = Settings::getGeneral_threads();
1601  if(threadCounts == 0)
1602  {
1603  threadCounts = (int)objectsDescriptors_.size();
1604  }
1605 
1606  QList<int> objectsDescriptorsId = objectsDescriptors_.keys();
1607  QList<cv::Mat> objectsDescriptorsMat = objectsDescriptors_.values();
1608  for(int j=0; j<objectsDescriptorsMat.size(); j+=threadCounts)
1609  {
1610  QVector<SearchThread*> threads;
1611 
1612  for(int k=j; k<j+threadCounts && k<objectsDescriptorsMat.size(); ++k)
1613  {
1614  threads.push_back(new SearchThread(vocabulary_, objectsDescriptorsId[k], &objectsDescriptorsMat[k], &words));
1615  threads.back()->start();
1616  }
1617 
1618  for(int k=0; k<threads.size(); ++k)
1619  {
1620  threads[k]->wait();
1621  info.matches_[threads[k]->getObjectId()] = threads[k]->getMatches();
1622 
1623  if(info.minMatchedDistance_ == -1 || info.minMatchedDistance_ > threads[k]->getMinMatchedDistance())
1624  {
1625  info.minMatchedDistance_ = threads[k]->getMinMatchedDistance();
1626  }
1627  if(info.maxMatchedDistance_ == -1 || info.maxMatchedDistance_ < threads[k]->getMaxMatchedDistance())
1628  {
1629  info.maxMatchedDistance_ = threads[k]->getMaxMatchedDistance();
1630  }
1631  delete threads[k];
1632  }
1633 
1634  }
1635  }
1636 
1637  info.timeStamps_.insert(DetectionInfo::kTimeMatching, time.restart());
1638 
1639  // Homographies
1640  if(Settings::getHomography_homographyComputed())
1641  {
1642  // HOMOGRAPHY
1643  UDEBUG("COMPUTE HOMOGRAPHY");
1644  int threadCounts = Settings::getGeneral_threads();
1645  if(threadCounts == 0)
1646  {
1647  threadCounts = info.matches_.size();
1648  }
1649  QList<int> matchesId = info.matches_.keys();
1650  QList<QMultiMap<int, int> > matchesList = info.matches_.values();
1651  for(int i=0; i<matchesList.size(); i+=threadCounts)
1652  {
1653  UDEBUG("Processing matches %d/%d", i+1, matchesList.size());
1654 
1655  QVector<HomographyThread*> threads;
1656 
1657  UDEBUG("Creating/Starting homography threads (%d)...", threadCounts);
1658  for(int k=i; k<i+threadCounts && k<matchesList.size(); ++k)
1659  {
1660  int objectId = matchesId[k];
1661  UASSERT(objects_.contains(objectId));
1662  threads.push_back(new HomographyThread(
1663  &matchesList[k],
1664  objectId,
1665  &objects_.value(objectId)->keypoints(),
1666  &info.sceneKeypoints_,
1667  objects_.value(objectId)->image(),
1668  grayscaleImg));
1669  threads.back()->start();
1670  }
1671  UDEBUG("Started homography threads");
1672 
1673  for(int j=0; j<threads.size(); ++j)
1674  {
1675  threads[j]->wait();
1676  UDEBUG("Processing results of homography thread %d", j);
1677 
1678  int id = threads[j]->getObjectId();
1679  QTransform hTransform;
1681  if(threads[j]->getHomography().empty())
1682  {
1683  code = threads[j]->rejectedCode();
1684  }
1685  if(code == DetectionInfo::kRejectedUndef &&
1686  threads[j]->getInliers().size() < Settings::getHomography_minimumInliers() )
1687  {
1689  }
1690  if(code == DetectionInfo::kRejectedUndef)
1691  {
1692  const cv::Mat & H = threads[j]->getHomography();
1693  UASSERT(H.cols == 3 && H.rows == 3 && H.type()==CV_64FC1);
1694  hTransform = QTransform(
1695  H.at<double>(0,0), H.at<double>(1,0), H.at<double>(2,0),
1696  H.at<double>(0,1), H.at<double>(1,1), H.at<double>(2,1),
1697  H.at<double>(0,2), H.at<double>(1,2), H.at<double>(2,2));
1698 
1699  // is homography valid?
1700  // Here we use mapToScene() from QGraphicsItem instead
1701  // of QTransform::map() because if the homography is not valid,
1702  // huge errors are set by the QGraphicsItem and not by QTransform::map();
1703  UASSERT(objects_.contains(id));
1704  QRectF objectRect = objects_.value(id)->rect();
1705  QGraphicsRectItem item(objectRect);
1706  item.setTransform(hTransform);
1707  QPolygonF rectH = item.mapToScene(item.rect());
1708 
1709  // If a point is outside of 2x times the surface of the scene, homography is invalid.
1710  for(int p=0; p<rectH.size(); ++p)
1711  {
1712  if((rectH.at(p).x() < -image.cols && rectH.at(p).x() < -objectRect.width()) ||
1713  (rectH.at(p).x() > image.cols*2 && rectH.at(p).x() > objectRect.width()*2) ||
1714  (rectH.at(p).y() < -image.rows && rectH.at(p).x() < -objectRect.height()) ||
1715  (rectH.at(p).y() > image.rows*2 && rectH.at(p).x() > objectRect.height()*2))
1716  {
1718  break;
1719  }
1720  }
1721 
1722  // angle
1723  if(code == DetectionInfo::kRejectedUndef &&
1724  Settings::getHomography_minAngle() > 0)
1725  {
1726  for(int a=0; a<rectH.size(); ++a)
1727  {
1728  // Find the smaller angle
1729  QLineF ab(rectH.at(a).x(), rectH.at(a).y(), rectH.at((a+1)%4).x(), rectH.at((a+1)%4).y());
1730  QLineF cb(rectH.at((a+1)%4).x(), rectH.at((a+1)%4).y(), rectH.at((a+2)%4).x(), rectH.at((a+2)%4).y());
1731  float angle = ab.angle(cb);
1732  float minAngle = (float)Settings::getHomography_minAngle();
1733  if(angle < minAngle ||
1734  angle > 180.0-minAngle)
1735  {
1737  break;
1738  }
1739  }
1740  }
1741 
1742  // multi detection
1743  if(code == DetectionInfo::kRejectedUndef &&
1744  Settings::getGeneral_multiDetection())
1745  {
1746  int distance = Settings::getGeneral_multiDetectionRadius(); // in pixels
1747  // Get the outliers and recompute homography with them
1748  matchesList.push_back(threads[j]->getOutliers());
1749  matchesId.push_back(id);
1750 
1751  // compute distance from previous added same objects...
1752  QMultiMap<int, QTransform>::iterator objIter = info.objDetected_.find(id);
1753  for(;objIter!=info.objDetected_.end() && objIter.key() == id; ++objIter)
1754  {
1755  qreal dx = objIter.value().m31() - hTransform.m31();
1756  qreal dy = objIter.value().m32() - hTransform.m32();
1757  int d = (int)sqrt(dx*dx + dy*dy);
1758  if(d < distance)
1759  {
1760  distance = d;
1761  }
1762  }
1763 
1764  if(distance < Settings::getGeneral_multiDetectionRadius())
1765  {
1767  }
1768  }
1769 
1770  // Corners visible
1771  if(code == DetectionInfo::kRejectedUndef &&
1772  Settings::getHomography_allCornersVisible())
1773  {
1774  // Now verify if all corners are in the scene
1775  QRectF sceneRect(0,0,image.cols, image.rows);
1776  for(int p=0; p<rectH.size(); ++p)
1777  {
1778  if(!sceneRect.contains(QPointF(rectH.at(p).x(), rectH.at(p).y())))
1779  {
1781  break;
1782  }
1783  }
1784  }
1785  }
1786 
1787  if(code == DetectionInfo::kRejectedUndef)
1788  {
1789  // Accepted!
1790  info.objDetected_.insert(id, hTransform);
1791  info.objDetectedSizes_.insert(id, objects_.value(id)->rect().size());
1792  info.objDetectedInliers_.insert(id, threads[j]->getInliers());
1793  info.objDetectedOutliers_.insert(id, threads[j]->getOutliers());
1794  info.objDetectedInliersCount_.insert(id, threads[j]->getInliers().size());
1795  info.objDetectedOutliersCount_.insert(id, threads[j]->getOutliers().size());
1796  info.objDetectedFilePaths_.insert(id, objects_.value(id)->filePath());
1797  }
1798  else
1799  {
1800  //Rejected!
1801  info.rejectedInliers_.insert(id, threads[j]->getInliers());
1802  info.rejectedOutliers_.insert(id, threads[j]->getOutliers());
1803  info.rejectedCodes_.insert(id, code);
1804  }
1805  delete threads[j];
1806  }
1807  UDEBUG("Processed matches %d", i+1);
1808  }
1809  info.timeStamps_.insert(DetectionInfo::kTimeHomography, time.restart());
1810  }
1811  }
1812  else if((descriptorsValid || vocabularyValid) && info.sceneKeypoints_.size())
1813  {
1814  UWARN("Cannot search, objects must be updated");
1815  }
1816  else if(info.sceneKeypoints_.size() == 0)
1817  {
1818  // Accept but warn the user
1819  UWARN("No features detected in the scene!?!");
1820  success = true;
1821  }
1822  }
1823 
1824  info.timeStamps_.insert(DetectionInfo::kTimeTotal, totalTime.elapsed());
1825 
1826  return success;
1827 }
1828 
1829 } // namespace find_object
d
const cv::Mat & image() const
Definition: FindObject.cpp:729
static void affineSkew(float tilt, float phi, const cv::Mat &image, cv::Mat &skewImage, cv::Mat &skewMask, cv::Mat &Ai)
Definition: FindObject.cpp:558
const cv::Mat & descriptors() const
Definition: FindObject.cpp:731
const cv::Mat & image() const
Definition: FindObject.cpp:633
static int getHomographyMethod()
Definition: Settings.cpp:1668
std::string uFormat(const char *fmt,...)
const QMultiMap< int, int > & wordToObjects() const
Definition: Vocabulary.h:49
static Feature2D * createKeypointDetector()
Definition: Settings.cpp:722
QMultiMap< int, int > matches_
f
QMultiMap< int, QString > objDetectedFilePaths_
Definition: DetectionInfo.h:73
virtual void detectAndCompute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:1763
QMap< int, cv::Mat > objectsDescriptors_
Definition: FindObject.h:106
XmlRpcServer s
std::vector< cv::KeyPoint > sceneKeypoints_
Definition: DetectionInfo.h:80
FindObject(bool keepImagesInRAM_=true, QObject *parent=0)
Definition: FindObject.cpp:51
const std::vector< int > & getIndexesB() const
bool detect(const cv::Mat &image, find_object::DetectionInfo &info) const
DetectionInfo::RejectedCode code_
QMultiMap< int, QSize > objDetectedSizes_
Definition: DetectionInfo.h:72
const QMultiMap< int, int > * sceneWords_
std::vector< cv::KeyPoint > limitKeypoints(const std::vector< cv::KeyPoint > &keypoints, int maxKeypoints)
Definition: FindObject.cpp:414
const cv::Mat & indexedDescriptors() const
Definition: Vocabulary.h:50
AffineExtractionThread(Feature2D *detector, Feature2D *extractor, const cv::Mat &image, float tilt, float phi)
Definition: FindObject.cpp:615
Some conversion functions.
QMultiMap< int, RejectedCode > rejectedCodes_
Definition: DetectionInfo.h:88
QMultiMap< int, int > getInliers() const
QMap< int, QMultiMap< int, int > > matches_
Definition: DetectionInfo.h:83
std::vector< int > indexesB_
static void setLevel(ULogger::Level level)
Definition: ULogger.h:301
bool loadSession(const QString &path, const ParametersMap &customParameters=ParametersMap())
Definition: FindObject.cpp:82
void addObjectAndUpdate(const cv::Mat &image, int id=0, const QString &filePath=QString())
Definition: FindObject.cpp:383
const std::list< std::string > & getFileNames() const
Definition: UDirectory.h:125
DetectionInfo::RejectedCode rejectedCode() const
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
#define UASSERT(condition)
static QString currentDetectorType()
Definition: Settings.cpp:1494
static const ParametersMap & getParameters()
Definition: Settings.h:338
QMultiMap< int, int > addWords(const cv::Mat &descriptors, int objectId)
Definition: Vocabulary.cpp:211
float getMaxMatchedDistance() const
void search(const cv::Mat &descriptors, cv::Mat &results, cv::Mat &dists, int k)
Definition: Vocabulary.cpp:434
void updateVocabulary(const QList< int > &ids=QList< int >())
Definition: FindObject.cpp:950
QMultiMap< int, int > getOutliers() const
QMultiMap< int, int > objDetectedInliersCount_
Definition: DetectionInfo.h:74
const std::vector< uchar > & getOutlierMask() const
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
int loadObjects(const QString &dirPath, bool recursive=false)
Definition: FindObject.cpp:236
QMap< TimeStamp, float > timeStamps_
Definition: DetectionInfo.h:79
virtual void detect(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat())
Definition: Settings.cpp:1721
void objectsFound(const find_object::DetectionInfo &, const find_object::Header &, const cv::Mat &, float)
Feature2D * extractor_
Definition: FindObject.h:109
bool loadVocabulary(const QString &filePath)
Definition: FindObject.cpp:196
QMap< int, ObjSignature * > objects_
Definition: FindObject.h:104
HomographyThread(const QMultiMap< int, int > *matches, int objectId, const std::vector< cv::KeyPoint > *kptsA, const std::vector< cv::KeyPoint > *kptsB, const cv::Mat &imageA, const cv::Mat &imageB)
QMultiMap< int, QTransform > objDetected_
Definition: DetectionInfo.h:71
ROSCPP_DECL bool ok()
void updateObjects(const QList< int > &ids=QList< int >())
Definition: FindObject.cpp:856
static void setParameter(const QString &key, const QVariant &value)
Definition: Settings.h:341
std::vector< cv::KeyPoint > keypoints_
Definition: FindObject.cpp:847
const std::vector< cv::KeyPoint > * kptsA_
QMap< QString, QVariant > ParametersMap
Definition: Settings.h:41
const Vocabulary * vocabulary() const
Definition: FindObject.h:89
static QString currentDescriptorType()
Definition: Settings.cpp:1500
QMultiMap< int, QMultiMap< int, int > > rejectedInliers_
Definition: DetectionInfo.h:86
static void setPrintWhere(bool printWhere)
Definition: ULogger.h:271
const std::vector< cv::KeyPoint > & keypoints() const
Definition: FindObject.cpp:730
Vocabulary * vocabulary_
Definition: FindObject.h:105
std::vector< uchar > outlierMask_
QMultiMap< int, QMultiMap< int, int > > objDetectedInliers_
Definition: DetectionInfo.h:76
std::vector< cv::KeyPoint > keypoints_
Definition: FindObject.cpp:696
ExtractFeaturesThread(Feature2D *detector, Feature2D *extractor, int objectId, const cv::Mat &image)
Definition: FindObject.cpp:708
void computeFeatures(Feature2D *detector, Feature2D *extractor, const cv::Mat &image, const cv::Mat &mask, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, int &timeDetection, int &timeExtraction)
Definition: FindObject.cpp:474
QMultiMap< int, int > objDetectedOutliersCount_
Definition: DetectionInfo.h:75
void load(QDataStream &streamSessionPtr, bool loadVocabularyOnly=false)
Definition: Vocabulary.cpp:112
void load(QDataStream &streamPtr, bool ignoreImage)
Definition: ObjSignature.h:133
virtual void compute(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors)
Definition: Settings.cpp:1742
void removeObject(int id)
Definition: FindObject.cpp:366
static bool in(Reader::Char c, Reader::Char c1, Reader::Char c2, Reader::Char c3, Reader::Char c4)
Definition: jsoncpp.cpp:244
const cv::Mat & descriptors() const
Definition: FindObject.cpp:635
#define UDEBUG(...)
bool saveSession(const QString &path)
Definition: FindObject.cpp:144
void save(QDataStream &streamSessionPtr, bool saveVocabularyOnly=false) const
Definition: Vocabulary.cpp:75
const QMultiMap< int, int > * matches_
float getMinMatchedDistance() const
QMultiMap< int, int > inliers_
#define UERROR(...)
const std::vector< int > & getIndexesA() const
QMultiMap< int, int > sceneWords_
Definition: DetectionInfo.h:82
ULogger class and convenient macros.
bool saveVocabulary(const QString &filePath) const
Definition: FindObject.cpp:172
const std::vector< cv::KeyPoint > * kptsB_
#define UWARN(...)
QMultiMap< int, QMultiMap< int, int > > rejectedOutliers_
Definition: DetectionInfo.h:87
const QMultiMap< int, int > & getMatches() const
static Feature2D * createDescriptorExtractor()
Definition: Settings.cpp:1138
SearchThread(Vocabulary *vocabulary, int objectId, const cv::Mat *descriptors, const QMultiMap< int, int > *sceneWords)
const cv::Mat * descriptors_
std::vector< int > indexesA_
QMultiMap< int, QMultiMap< int, int > > objDetectedOutliers_
Definition: DetectionInfo.h:77
QMultiMap< int, int > outliers_
const ObjSignature * addObject(const QString &filePath)
Definition: FindObject.cpp:283
QMap< int, int > dataRange_
Definition: FindObject.h:107
const std::string response
const cv::Mat & getHomography() const
void removeObjectAndUpdate(int id)
Definition: FindObject.cpp:395
const std::vector< cv::KeyPoint > & keypoints() const
Definition: FindObject.cpp:634
#define UINFO(...)


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