Features2d.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, 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 
29 #include "rtabmap/core/util3d.h"
31 #include "rtabmap/core/Stereo.h"
32 #include "rtabmap/core/util2d.h"
33 #include "rtabmap/utilite/UStl.h"
36 #include "rtabmap/utilite/UMath.h"
38 #include "rtabmap/utilite/UTimer.h"
39 #include <opencv2/imgproc/imgproc_c.h>
40 #include <opencv2/core/version.hpp>
41 #include <opencv2/opencv_modules.hpp>
42 
43 #ifdef RTABMAP_ORB_OCTREE
44 #include "opencv/ORBextractor.h"
45 #endif
46 
47 #ifdef RTABMAP_TORCH
49 #endif
50 
51 #ifdef RTABMAP_PYTHON
52 #include "python/PyDetector.h"
53 #endif
54 
55 #if CV_MAJOR_VERSION < 3
56 #include "opencv/Orb.h"
57 #ifdef HAVE_OPENCV_GPU
58 #include <opencv2/gpu/gpu.hpp>
59 #endif
60 #else
61 #include <opencv2/core/cuda.hpp>
62 #endif
63 
64 #ifdef HAVE_OPENCV_NONFREE
65  #if CV_MAJOR_VERSION == 2 && CV_MINOR_VERSION >=4
66  #include <opencv2/nonfree/gpu.hpp>
67  #include <opencv2/nonfree/features2d.hpp>
68  #endif
69 #endif
70 #ifdef HAVE_OPENCV_XFEATURES2D
71  #include <opencv2/xfeatures2d.hpp>
72  #include <opencv2/xfeatures2d/nonfree.hpp>
73  #include <opencv2/xfeatures2d/cuda.hpp>
74 #endif
75 #ifdef HAVE_OPENCV_CUDAFEATURES2D
76  #include <opencv2/cudafeatures2d.hpp>
77 #endif
78 
79 #ifdef RTABMAP_FASTCV
80 #include <fastcv.h>
81 #endif
82 
83 namespace rtabmap {
84 
86  std::vector<cv::KeyPoint> & keypoints,
87  const cv::Mat & depth,
88  float minDepth,
89  float maxDepth)
90 {
91  cv::Mat descriptors;
92  filterKeypointsByDepth(keypoints, descriptors, depth, minDepth, maxDepth);
93 }
94 
96  std::vector<cv::KeyPoint> & keypoints,
97  cv::Mat & descriptors,
98  const cv::Mat & depth,
99  float minDepth,
100  float maxDepth)
101 {
102  UASSERT(minDepth >= 0.0f);
103  UASSERT(maxDepth <= 0.0f || maxDepth > minDepth);
104  if(!depth.empty() && (descriptors.empty() || descriptors.rows == (int)keypoints.size()))
105  {
106  std::vector<cv::KeyPoint> output(keypoints.size());
107  std::vector<int> indexes(keypoints.size(), 0);
108  int oi=0;
109  bool isInMM = depth.type() == CV_16UC1;
110  for(unsigned int i=0; i<keypoints.size(); ++i)
111  {
112  int u = int(keypoints[i].pt.x+0.5f);
113  int v = int(keypoints[i].pt.y+0.5f);
114  if(u >=0 && u<depth.cols && v >=0 && v<depth.rows)
115  {
116  float d = isInMM?(float)depth.at<uint16_t>(v,u)*0.001f:depth.at<float>(v,u);
117  if(uIsFinite(d) && d>minDepth && (maxDepth <= 0.0f || d < maxDepth))
118  {
119  output[oi++] = keypoints[i];
120  indexes[i] = 1;
121  }
122  }
123  }
124  output.resize(oi);
125  keypoints = output;
126 
127  if(!descriptors.empty() && (int)keypoints.size() != descriptors.rows)
128  {
129  if(keypoints.size() == 0)
130  {
131  descriptors = cv::Mat();
132  }
133  else
134  {
135  cv::Mat newDescriptors((int)keypoints.size(), descriptors.cols, descriptors.type());
136  int di = 0;
137  for(unsigned int i=0; i<indexes.size(); ++i)
138  {
139  if(indexes[i] == 1)
140  {
141  if(descriptors.type() == CV_32FC1)
142  {
143  memcpy(newDescriptors.ptr<float>(di++), descriptors.ptr<float>(i), descriptors.cols*sizeof(float));
144  }
145  else // CV_8UC1
146  {
147  memcpy(newDescriptors.ptr<char>(di++), descriptors.ptr<char>(i), descriptors.cols*sizeof(char));
148  }
149  }
150  }
151  descriptors = newDescriptors;
152  }
153  }
154  }
155 }
156 
158  std::vector<cv::KeyPoint> & keypoints,
159  cv::Mat & descriptors,
160  std::vector<cv::Point3f> & keypoints3D,
161  float minDepth,
162  float maxDepth)
163 {
164  UDEBUG("");
165  //remove all keypoints/descriptors with no valid 3D points
166  UASSERT(((int)keypoints.size() == descriptors.rows || descriptors.empty()) &&
167  keypoints3D.size() == keypoints.size());
168  std::vector<cv::KeyPoint> validKeypoints(keypoints.size());
169  std::vector<cv::Point3f> validKeypoints3D(keypoints.size());
170  cv::Mat validDescriptors(descriptors.size(), descriptors.type());
171 
172  int oi=0;
173  float minDepthSqr = minDepth * minDepth;
174  float maxDepthSqr = maxDepth * maxDepth;
175  for(unsigned int i=0; i<keypoints3D.size(); ++i)
176  {
177  cv::Point3f & pt = keypoints3D[i];
178  if(util3d::isFinite(pt))
179  {
180  float distSqr = pt.x*pt.x+pt.y*pt.y+pt.z*pt.z;
181  if(distSqr >= minDepthSqr && (maxDepthSqr==0.0f || distSqr <= maxDepthSqr))
182  {
183  validKeypoints[oi] = keypoints[i];
184  validKeypoints3D[oi] = pt;
185  if(!descriptors.empty())
186  {
187  descriptors.row(i).copyTo(validDescriptors.row(oi));
188  }
189  ++oi;
190  }
191  }
192  }
193  UDEBUG("Removed %d invalid 3D points", (int)keypoints3D.size()-oi);
194  validKeypoints.resize(oi);
195  validKeypoints3D.resize(oi);
196  keypoints = validKeypoints;
197  keypoints3D = validKeypoints3D;
198  if(!descriptors.empty())
199  {
200  descriptors = validDescriptors.rowRange(0, oi).clone();
201  }
202 }
203 
205  std::vector<cv::KeyPoint> & keypoints,
206  const cv::Mat & disparity,
207  float minDisparity)
208 {
209  cv::Mat descriptors;
210  filterKeypointsByDisparity(keypoints, descriptors, disparity, minDisparity);
211 }
212 
214  std::vector<cv::KeyPoint> & keypoints,
215  cv::Mat & descriptors,
216  const cv::Mat & disparity,
217  float minDisparity)
218 {
219  if(!disparity.empty() && minDisparity > 0.0f && (descriptors.empty() || descriptors.rows == (int)keypoints.size()))
220  {
221  std::vector<cv::KeyPoint> output(keypoints.size());
222  std::vector<int> indexes(keypoints.size(), 0);
223  int oi=0;
224  for(unsigned int i=0; i<keypoints.size(); ++i)
225  {
226  int u = int(keypoints[i].pt.x+0.5f);
227  int v = int(keypoints[i].pt.y+0.5f);
228  if(u >=0 && u<disparity.cols && v >=0 && v<disparity.rows)
229  {
230  float d = disparity.type() == CV_16SC1?float(disparity.at<short>(v,u))/16.0f:disparity.at<float>(v,u);
231  if(d!=0.0f && uIsFinite(d) && d >= minDisparity)
232  {
233  output[oi++] = keypoints[i];
234  indexes[i] = 1;
235  }
236  }
237  }
238  output.resize(oi);
239  keypoints = output;
240 
241  if(!descriptors.empty() && (int)keypoints.size() != descriptors.rows)
242  {
243  if(keypoints.size() == 0)
244  {
245  descriptors = cv::Mat();
246  }
247  else
248  {
249  cv::Mat newDescriptors((int)keypoints.size(), descriptors.cols, descriptors.type());
250  int di = 0;
251  for(unsigned int i=0; i<indexes.size(); ++i)
252  {
253  if(indexes[i] == 1)
254  {
255  if(descriptors.type() == CV_32FC1)
256  {
257  memcpy(newDescriptors.ptr<float>(di++), descriptors.ptr<float>(i), descriptors.cols*sizeof(float));
258  }
259  else // CV_8UC1
260  {
261  memcpy(newDescriptors.ptr<char>(di++), descriptors.ptr<char>(i), descriptors.cols*sizeof(char));
262  }
263  }
264  }
265  descriptors = newDescriptors;
266  }
267  }
268  }
269 }
270 
271 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, int maxKeypoints)
272 {
273  cv::Mat descriptors;
274  limitKeypoints(keypoints, descriptors, maxKeypoints);
275 }
276 
277 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints)
278 {
279  std::vector<cv::Point3f> keypoints3D;
280  limitKeypoints(keypoints, keypoints3D, descriptors, maxKeypoints);
281 }
282 
283 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors, int maxKeypoints)
284 {
285  UASSERT_MSG((int)keypoints.size() == descriptors.rows || descriptors.rows == 0, uFormat("keypoints=%d descriptors=%d", (int)keypoints.size(), descriptors.rows).c_str());
286  UASSERT_MSG(keypoints.size() == keypoints3D.size() || keypoints3D.size() == 0, uFormat("keypoints=%d keypoints3D=%d", (int)keypoints.size(), (int)keypoints3D.size()).c_str());
287  if(maxKeypoints > 0 && (int)keypoints.size() > maxKeypoints)
288  {
289  UTimer timer;
290  ULOGGER_DEBUG("too much words (%d), removing words with the hessian threshold", keypoints.size());
291  // Remove words under the new hessian threshold
292 
293  // Sort words by hessian
294  std::multimap<float, int> hessianMap; // <hessian,id>
295  for(unsigned int i = 0; i <keypoints.size(); ++i)
296  {
297  //Keep track of the data, to be easier to manage the data in the next step
298  hessianMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
299  }
300 
301  // Remove them from the signature
302  int removed = (int)hessianMap.size()-maxKeypoints;
303  std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
304  std::vector<cv::KeyPoint> kptsTmp(maxKeypoints);
305  std::vector<cv::Point3f> kpts3DTmp;
306  if(!keypoints3D.empty())
307  {
308  kpts3DTmp.resize(maxKeypoints);
309  }
310  cv::Mat descriptorsTmp;
311  if(descriptors.rows)
312  {
313  descriptorsTmp = cv::Mat(maxKeypoints, descriptors.cols, descriptors.type());
314  }
315  for(unsigned int k=0; k < kptsTmp.size() && iter!=hessianMap.rend(); ++k, ++iter)
316  {
317  kptsTmp[k] = keypoints[iter->second];
318  if(keypoints3D.size())
319  {
320  kpts3DTmp[k] = keypoints3D[iter->second];
321  }
322  if(descriptors.rows)
323  {
324  if(descriptors.type() == CV_32FC1)
325  {
326  memcpy(descriptorsTmp.ptr<float>(k), descriptors.ptr<float>(iter->second), descriptors.cols*sizeof(float));
327  }
328  else
329  {
330  memcpy(descriptorsTmp.ptr<char>(k), descriptors.ptr<char>(iter->second), descriptors.cols*sizeof(char));
331  }
332  }
333  }
334  ULOGGER_DEBUG("%d keypoints removed, (kept %d), minimum response=%f", removed, (int)kptsTmp.size(), kptsTmp.size()?kptsTmp.back().response:0.0f);
335  ULOGGER_DEBUG("removing words time = %f s", timer.ticks());
336  keypoints = kptsTmp;
337  keypoints3D = kpts3DTmp;
338  if(descriptors.rows)
339  {
340  descriptors = descriptorsTmp;
341  }
342  }
343 }
344 
345 void Feature2D::limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints)
346 {
347  if(maxKeypoints > 0 && (int)keypoints.size() > maxKeypoints)
348  {
349  UTimer timer;
350  ULOGGER_DEBUG("too much words (%d), removing words with the hessian threshold", (int)keypoints.size());
351  // Remove words under the new hessian threshold
352 
353  // Sort words by hessian
354  std::multimap<float, int> hessianMap; // <hessian,id>
355  for(unsigned int i = 0; i <keypoints.size(); ++i)
356  {
357  //Keep track of the data, to be easier to manage the data in the next step
358  hessianMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
359  }
360 
361  // Keep keypoints with highest response
362  int removed = (int)hessianMap.size()-maxKeypoints;
363  std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
364  inliers.resize(keypoints.size(), false);
365  float minimumHessian = 0.0f;
366  for(int k=0; k < maxKeypoints && iter!=hessianMap.rend(); ++k, ++iter)
367  {
368  inliers[iter->second] = true;
369  minimumHessian = iter->first;
370  }
371  ULOGGER_DEBUG("%d keypoints removed, (kept %d), minimum response=%f", removed, maxKeypoints, minimumHessian);
372  ULOGGER_DEBUG("filter keypoints time = %f s", timer.ticks());
373  }
374  else
375  {
376  ULOGGER_DEBUG("keeping all %d keypoints", (int)keypoints.size());
377  inliers.resize(keypoints.size(), true);
378  }
379 }
380 
381 void Feature2D::limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints, const cv::Size & imageSize, int gridRows, int gridCols)
382 {
383  if(maxKeypoints <= 0 || (int)keypoints.size() <= maxKeypoints)
384  {
385  inliers.resize(keypoints.size(), true);
386  return;
387  }
388  UASSERT(gridCols>=1 && gridRows >=1);
389  UASSERT(imageSize.height>gridRows && imageSize.width>gridCols);
390  int rowSize = imageSize.height / gridRows;
391  int colSize = imageSize.width / gridCols;
392  int maxKeypointsPerCell = maxKeypoints / (gridRows * gridCols);
393  std::vector<std::vector<cv::KeyPoint> > keypointsPerCell(gridRows * gridCols);
394  std::vector<std::vector<int> > indexesPerCell(gridRows * gridCols);
395  for(size_t i=0; i<keypoints.size(); ++i)
396  {
397  int cellRow = int(keypoints[i].pt.y)/rowSize;
398  int cellCol = int(keypoints[i].pt.x)/colSize;
399  UASSERT(cellRow >=0 && cellRow < gridRows);
400  UASSERT(cellCol >=0 && cellCol < gridCols);
401 
402  keypointsPerCell[cellRow*gridCols + cellCol].push_back(keypoints[i]);
403  indexesPerCell[cellRow*gridCols + cellCol].push_back(i);
404  }
405  inliers.resize(keypoints.size(), false);
406  for(size_t i=0; i<keypointsPerCell.size(); ++i)
407  {
408  std::vector<bool> inliersCell;
409  limitKeypoints(keypointsPerCell[i], inliersCell, maxKeypointsPerCell);
410  for(size_t j=0; j<inliersCell.size(); ++j)
411  {
412  if(inliersCell[j])
413  {
414  inliers.at(indexesPerCell[i][j]) = true;
415  }
416  }
417  }
418 }
419 
420 cv::Rect Feature2D::computeRoi(const cv::Mat & image, const std::string & roiRatios)
421 {
422  return util2d::computeRoi(image, roiRatios);
423 }
424 
425 cv::Rect Feature2D::computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios)
426 {
427  return util2d::computeRoi(image, roiRatios);
428 }
429 
431 // Feature2D
433 Feature2D::Feature2D(const ParametersMap & parameters) :
434  maxFeatures_(Parameters::defaultKpMaxFeatures()),
435  _maxDepth(Parameters::defaultKpMaxDepth()),
436  _minDepth(Parameters::defaultKpMinDepth()),
437  _roiRatios(std::vector<float>(4, 0.0f)),
438  _subPixWinSize(Parameters::defaultKpSubPixWinSize()),
439  _subPixIterations(Parameters::defaultKpSubPixIterations()),
440  _subPixEps(Parameters::defaultKpSubPixEps()),
441  gridRows_(Parameters::defaultKpGridRows()),
442  gridCols_(Parameters::defaultKpGridCols())
443 {
444  _stereo = new Stereo(parameters);
445  this->parseParameters(parameters);
446 }
448 {
449  delete _stereo;
450 }
452 {
453  uInsert(parameters_, parameters);
454 
455  Parameters::parse(parameters, Parameters::kKpMaxFeatures(), maxFeatures_);
456  Parameters::parse(parameters, Parameters::kKpMaxDepth(), _maxDepth);
457  Parameters::parse(parameters, Parameters::kKpMinDepth(), _minDepth);
458  Parameters::parse(parameters, Parameters::kKpSubPixWinSize(), _subPixWinSize);
459  Parameters::parse(parameters, Parameters::kKpSubPixIterations(), _subPixIterations);
460  Parameters::parse(parameters, Parameters::kKpSubPixEps(), _subPixEps);
461  Parameters::parse(parameters, Parameters::kKpGridRows(), gridRows_);
462  Parameters::parse(parameters, Parameters::kKpGridCols(), gridCols_);
463 
464  UASSERT(gridRows_ >= 1 && gridCols_>=1);
465 
466  // convert ROI from string to vector
467  ParametersMap::const_iterator iter;
468  if((iter=parameters.find(Parameters::kKpRoiRatios())) != parameters.end())
469  {
470  std::list<std::string> strValues = uSplit(iter->second, ' ');
471  if(strValues.size() != 4)
472  {
473  ULOGGER_ERROR("The number of values must be 4 (roi=\"%s\")", iter->second.c_str());
474  }
475  else
476  {
477  std::vector<float> tmpValues(4);
478  unsigned int i=0;
479  for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
480  {
481  tmpValues[i] = uStr2Float(*jter);
482  ++i;
483  }
484 
485  if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0f-tmpValues[1] &&
486  tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0f-tmpValues[0] &&
487  tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0f-tmpValues[3] &&
488  tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0f-tmpValues[2])
489  {
490  _roiRatios = tmpValues;
491  }
492  else
493  {
494  ULOGGER_ERROR("The roi ratios are not valid (roi=\"%s\")", iter->second.c_str());
495  }
496  }
497  }
498 
499  //stereo
500  UASSERT(_stereo != 0);
501  if((iter=parameters.find(Parameters::kStereoOpticalFlow())) != parameters.end())
502  {
503  delete _stereo;
505  }
506  else
507  {
508  _stereo->parseParameters(parameters);
509  }
510 }
512 {
513  int type = Parameters::defaultKpDetectorStrategy();
514  Parameters::parse(parameters, Parameters::kKpDetectorStrategy(), type);
515  return create((Feature2D::Type)type, parameters);
516 }
518 {
519 
520 // NONFREE checks
521 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
522 
523  #ifndef RTABMAP_NONFREE
525  {
526  #if CV_MAJOR_VERSION < 3
527  UWARN("SURF and SIFT features cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
528  #else
529  UWARN("SURF and SIFT features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
530  #endif
532  }
533  #endif
534 
535 #else // >= 4.4.0 >= 3.4.11
536 
537  #ifndef RTABMAP_NONFREE
538  if(type == Feature2D::kFeatureSurf)
539  {
540  UWARN("SURF features cannot be used because OpenCV was not built with nonfree module. SIFT is used instead.");
542  }
544  {
545  UWARN("SURF detector cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
547  }
548  #endif
549 
550 #endif // >= 4.4.0 >= 3.4.11
551 
552 #if !defined(HAVE_OPENCV_XFEATURES2D) && CV_MAJOR_VERSION >= 3
553  if(type == Feature2D::kFeatureFastBrief ||
560  {
561  UWARN("BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
563  }
564 #elif CV_MAJOR_VERSION < 3
565  if(type == Feature2D::kFeatureKaze)
566  {
567  #ifdef RTABMAP_NONFREE
568  UWARN("KAZE detector/descriptor can be used only with OpenCV3. SURF is used instead.");
570  #else
571  UWARN("KAZE detector/descriptor can be used only with OpenCV3. GFTT/ORB is used instead.");
573  #endif
574  }
576  {
577  UWARN("DAISY detector/descriptor can be used only with OpenCV3. GFTT/BRIEF is used instead.");
579  }
580 #endif
581 
582 
583 #ifndef RTABMAP_ORB_OCTREE
584  if(type == Feature2D::kFeatureOrbOctree)
585  {
586  UWARN("ORB OcTree feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
588  }
589 #endif
590 
591 #ifndef RTABMAP_TORCH
593  {
594  UWARN("SupertPoint Torch feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
596  }
597 #endif
598 
599  Feature2D * feature2D = 0;
600  switch(type)
601  {
603  feature2D = new SURF(parameters);
604  break;
606  feature2D = new SIFT(parameters);
607  break;
609  feature2D = new ORB(parameters);
610  break;
612  feature2D = new FAST_BRIEF(parameters);
613  break;
615  feature2D = new FAST_FREAK(parameters);
616  break;
618  feature2D = new GFTT_FREAK(parameters);
619  break;
621  feature2D = new GFTT_BRIEF(parameters);
622  break;
624  feature2D = new GFTT_ORB(parameters);
625  break;
627  feature2D = new BRISK(parameters);
628  break;
630  feature2D = new KAZE(parameters);
631  break;
633  feature2D = new ORBOctree(parameters);
634  break;
635 #ifdef RTABMAP_TORCH
637  feature2D = new SuperPointTorch(parameters);
638  break;
639 #endif
641  feature2D = new SURF_FREAK(parameters);
642  break;
644  feature2D = new GFTT_DAISY(parameters);
645  break;
647  feature2D = new SURF_DAISY(parameters);
648  break;
649 #ifdef RTABMAP_PYTHON
651  feature2D = new PyDetector(parameters);
652  break;
653 #endif
654 #ifdef RTABMAP_NONFREE
655  default:
656  feature2D = new SURF(parameters);
658  break;
659 #else
660  default:
661  feature2D = new ORB(parameters);
663  break;
664 #endif
665 
666  }
667  return feature2D;
668 }
669 
670 std::vector<cv::KeyPoint> Feature2D::generateKeypoints(const cv::Mat & image, const cv::Mat & maskIn)
671 {
672  UASSERT(!image.empty());
673  UASSERT(image.type() == CV_8UC1);
674 
675  cv::Mat mask;
676  if(!maskIn.empty())
677  {
678  if(maskIn.type()==CV_16UC1 || maskIn.type() == CV_32FC1)
679  {
680  mask = cv::Mat::zeros(maskIn.rows, maskIn.cols, CV_8UC1);
681  for(int i=0; i<(int)mask.total(); ++i)
682  {
683  float value = 0.0f;
684  if(maskIn.type()==CV_16UC1)
685  {
686  if(((unsigned short*)maskIn.data)[i] > 0 &&
687  ((unsigned short*)maskIn.data)[i] < std::numeric_limits<unsigned short>::max())
688  {
689  value = float(((unsigned short*)maskIn.data)[i])*0.001f;
690  }
691  }
692  else
693  {
694  value = ((float*)maskIn.data)[i];
695  }
696 
697  if(value>_minDepth &&
698  (_maxDepth == 0.0f || value <= _maxDepth) &&
699  uIsFinite(value))
700  {
701  ((unsigned char*)mask.data)[i] = 255; // ORB uses 255 to handle pyramids
702  }
703  }
704  }
705  else if(maskIn.type()==CV_8UC1)
706  {
707  // assume a standard mask
708  mask = maskIn;
709  }
710  else
711  {
712  UERROR("Wrong mask type (%d)! Should be 8UC1, 16UC1 or 32FC1.", maskIn.type());
713  }
714  }
715 
716  UASSERT(mask.empty() || (mask.cols == image.cols && mask.rows == image.rows));
717 
718  std::vector<cv::KeyPoint> keypoints;
719  UTimer timer;
720  cv::Rect globalRoi = Feature2D::computeRoi(image, _roiRatios);
721  if(!(globalRoi.width && globalRoi.height))
722  {
723  globalRoi = cv::Rect(0,0,image.cols, image.rows);
724  }
725 
726  // Get keypoints
727  int rowSize = globalRoi.height / gridRows_;
728  int colSize = globalRoi.width / gridCols_;
729  int maxFeatures = maxFeatures_ / (gridRows_ * gridCols_);
730  for (int i = 0; i<gridRows_; ++i)
731  {
732  for (int j = 0; j<gridCols_; ++j)
733  {
734  cv::Rect roi(globalRoi.x + j*colSize, globalRoi.y + i*rowSize, colSize, rowSize);
735  std::vector<cv::KeyPoint> sub_keypoints;
736  sub_keypoints = this->generateKeypointsImpl(image, roi, mask);
737  limitKeypoints(sub_keypoints, maxFeatures);
738  if(roi.x || roi.y)
739  {
740  // Adjust keypoint position to raw image
741  for(std::vector<cv::KeyPoint>::iterator iter=sub_keypoints.begin(); iter!=sub_keypoints.end(); ++iter)
742  {
743  iter->pt.x += roi.x;
744  iter->pt.y += roi.y;
745  }
746  }
747  keypoints.insert( keypoints.end(), sub_keypoints.begin(), sub_keypoints.end() );
748  }
749  }
750  UDEBUG("Keypoints extraction time = %f s, keypoints extracted = %d (grid=%dx%d, mask empty=%d)",
751  timer.ticks(), keypoints.size(), gridCols_, gridRows_, mask.empty()?1:0);
752 
753  if(keypoints.size() && _subPixWinSize > 0 && _subPixIterations > 0)
754  {
755  std::vector<cv::Point2f> corners;
756  cv::KeyPoint::convert(keypoints, corners);
757  cv::cornerSubPix( image, corners,
758  cv::Size( _subPixWinSize, _subPixWinSize ),
759  cv::Size( -1, -1 ),
760  cv::TermCriteria( CV_TERMCRIT_ITER | CV_TERMCRIT_EPS, _subPixIterations, _subPixEps ) );
761 
762  for(unsigned int i=0;i<corners.size(); ++i)
763  {
764  keypoints[i].pt = corners[i];
765  }
766  UDEBUG("subpixel time = %f s", timer.ticks());
767  }
768 
769  return keypoints;
770 }
771 
773  const cv::Mat & image,
774  std::vector<cv::KeyPoint> & keypoints) const
775 {
776  cv::Mat descriptors;
777  if(keypoints.size())
778  {
779  UASSERT(!image.empty());
780  UASSERT(image.type() == CV_8UC1);
781  descriptors = generateDescriptorsImpl(image, keypoints);
782  UASSERT_MSG(descriptors.rows == (int)keypoints.size(), uFormat("descriptors=%d, keypoints=%d", descriptors.rows, (int)keypoints.size()).c_str());
783  UDEBUG("Descriptors extracted = %d, remaining kpts=%d", descriptors.rows, (int)keypoints.size());
784  }
785  return descriptors;
786 }
787 
788 std::vector<cv::Point3f> Feature2D::generateKeypoints3D(
789  const SensorData & data,
790  const std::vector<cv::KeyPoint> & keypoints) const
791 {
792  std::vector<cv::Point3f> keypoints3D;
793  if(keypoints.size())
794  {
795  if(!data.rightRaw().empty() && !data.imageRaw().empty() &&
796  !data.stereoCameraModels().empty() &&
797  data.stereoCameraModels()[0].isValidForProjection())
798  {
799  //stereo
800  cv::Mat imageMono;
801  // convert to grayscale
802  if(data.imageRaw().channels() > 1)
803  {
804  cv::cvtColor(data.imageRaw(), imageMono, cv::COLOR_BGR2GRAY);
805  }
806  else
807  {
808  imageMono = data.imageRaw();
809  }
810 
811  std::vector<cv::Point2f> leftCorners;
812  cv::KeyPoint::convert(keypoints, leftCorners);
813 
814  std::vector<cv::Point2f> rightCorners;
815 
816  if(data.stereoCameraModels().size() == 1)
817  {
818  std::vector<unsigned char> status;
819  rightCorners = _stereo->computeCorrespondences(
820  imageMono,
821  data.rightRaw(),
822  leftCorners,
823  status);
824 
826  {
827  int rejected = 0;
828  for(size_t i=0; i<status.size(); ++i)
829  {
830  if(status[i]==0)
831  {
832  ++rejected;
833  }
834  }
835  if(rejected > (int)status.size()/2)
836  {
837  UWARN("A large number (%d/%d) of stereo correspondences are rejected! "
838  "Optical flow may have failed because images are not calibrated, "
839  "the background is too far (no disparity between the images), "
840  "maximum disparity may be too small (%f) or that exposure between "
841  "left and right images is too different.",
842  rejected,
843  (int)status.size(),
844  _stereo->maxDisparity());
845  }
846  }
847 
848  keypoints3D = util3d::generateKeypoints3DStereo(
849  leftCorners,
850  rightCorners,
851  data.stereoCameraModels()[0],
852  status,
853  _minDepth,
854  _maxDepth);
855  }
856  else
857  {
858  int subImageWith = imageMono.cols / data.stereoCameraModels().size();
859  UASSERT(imageMono.cols % subImageWith == 0);
860  std::vector<std::vector<cv::Point2f> > subLeftCorners(data.stereoCameraModels().size());
861  std::vector<std::vector<int> > subIndex(data.stereoCameraModels().size());
862  // Assign keypoints per camera
863  for(size_t i=0; i<leftCorners.size(); ++i)
864  {
865  int cameraIndex = int(leftCorners[i].x / subImageWith);
866  leftCorners[i].x -= cameraIndex*subImageWith;
867  subLeftCorners[cameraIndex].push_back(leftCorners[i]);
868  subIndex[cameraIndex].push_back(i);
869  }
870 
871  keypoints3D.resize(keypoints.size());
872  int total = 0;
873  int rejected = 0;
874  for(size_t i=0; i<data.stereoCameraModels().size(); ++i)
875  {
876  if(!subLeftCorners[i].empty())
877  {
878  std::vector<unsigned char> status;
879  rightCorners = _stereo->computeCorrespondences(
880  imageMono.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
881  data.rightRaw().colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
882  subLeftCorners[i],
883  status);
884 
885  std::vector<cv::Point3f> subKeypoints3D = util3d::generateKeypoints3DStereo(
886  subLeftCorners[i],
887  rightCorners,
888  data.stereoCameraModels()[i],
889  status,
890  _minDepth,
891  _maxDepth);
892 
894  {
895  for(size_t i=0; i<status.size(); ++i)
896  {
897  if(status[i]==0)
898  {
899  ++rejected;
900  }
901  }
902  total+=status.size();
903  }
904 
905  UASSERT(subIndex[i].size() == subKeypoints3D.size());
906  for(size_t j=0; j<subKeypoints3D.size(); ++j)
907  {
908  keypoints3D[subIndex[i][j]] = subKeypoints3D[j];
909  }
910  }
911  }
912 
914  {
915  if(rejected > total/2)
916  {
917  UWARN("A large number (%d/%d) of stereo correspondences are rejected! "
918  "Optical flow may have failed because images are not calibrated, "
919  "the background is too far (no disparity between the images), "
920  "maximum disparity may be too small (%f) or that exposure between "
921  "left and right images is too different.",
922  rejected,
923  total,
924  _stereo->maxDisparity());
925  }
926  }
927  }
928  }
929  else if(!data.depthRaw().empty() && data.cameraModels().size())
930  {
931  keypoints3D = util3d::generateKeypoints3DDepth(
932  keypoints,
933  data.depthOrRightRaw(),
934  data.cameraModels(),
935  _minDepth,
936  _maxDepth);
937  }
938  }
939 
940  return keypoints3D;
941 }
942 
944 //SURF
946 SURF::SURF(const ParametersMap & parameters) :
947  hessianThreshold_(Parameters::defaultSURFHessianThreshold()),
948  nOctaves_(Parameters::defaultSURFOctaves()),
949  nOctaveLayers_(Parameters::defaultSURFOctaveLayers()),
950  extended_(Parameters::defaultSURFExtended()),
951  upright_(Parameters::defaultSURFUpright()),
952  gpuKeypointsRatio_(Parameters::defaultSURFGpuKeypointsRatio()),
953  gpuVersion_(Parameters::defaultSURFGpuVersion())
954 {
955  parseParameters(parameters);
956 }
957 
959 {
960 }
961 
962 void SURF::parseParameters(const ParametersMap & parameters)
963 {
964  Feature2D::parseParameters(parameters);
965 
966  Parameters::parse(parameters, Parameters::kSURFExtended(), extended_);
967  Parameters::parse(parameters, Parameters::kSURFHessianThreshold(), hessianThreshold_);
968  Parameters::parse(parameters, Parameters::kSURFOctaveLayers(), nOctaveLayers_);
969  Parameters::parse(parameters, Parameters::kSURFOctaves(), nOctaves_);
970  Parameters::parse(parameters, Parameters::kSURFUpright(), upright_);
971  Parameters::parse(parameters, Parameters::kSURFGpuKeypointsRatio(), gpuKeypointsRatio_);
972  Parameters::parse(parameters, Parameters::kSURFGpuVersion(), gpuVersion_);
973 
974 #ifdef RTABMAP_NONFREE
975 #if CV_MAJOR_VERSION < 3
976  if(gpuVersion_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
977  {
978  UWARN("GPU version of SURF not available! Using CPU version instead...");
979  gpuVersion_ = false;
980  }
981 #else
982  if(gpuVersion_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
983  {
984  UWARN("GPU version of SURF not available! Using CPU version instead...");
985  gpuVersion_ = false;
986  }
987 #endif
988  if(gpuVersion_)
989  {
991  }
992  else
993  {
994 #if CV_MAJOR_VERSION < 3
996 #else
998 #endif
999  }
1000 #else
1001  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1002 #endif
1003 }
1004 
1005 std::vector<cv::KeyPoint> SURF::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1006 {
1007  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1008  std::vector<cv::KeyPoint> keypoints;
1009 
1010 #ifdef RTABMAP_NONFREE
1011  cv::Mat imgRoi(image, roi);
1012  cv::Mat maskRoi;
1013  if(!mask.empty())
1014  {
1015  maskRoi = cv::Mat(mask, roi);
1016  }
1017  if(gpuVersion_)
1018  {
1019 #if CV_MAJOR_VERSION < 3
1020  cv::gpu::GpuMat imgGpu(imgRoi);
1021  cv::gpu::GpuMat maskGpu(maskRoi);
1022  (*_gpuSurf.obj)(imgGpu, maskGpu, keypoints);
1023 #else
1024  cv::cuda::GpuMat imgGpu(imgRoi);
1025  cv::cuda::GpuMat maskGpu(maskRoi);
1026  (*_gpuSurf.get())(imgGpu, maskGpu, keypoints);
1027 #endif
1028  }
1029  else
1030  {
1031  _surf->detect(imgRoi, keypoints, maskRoi);
1032  }
1033 #else
1034  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1035 #endif
1036  return keypoints;
1037 }
1038 
1039 cv::Mat SURF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1040 {
1041  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1042  cv::Mat descriptors;
1043 #ifdef RTABMAP_NONFREE
1044  if(gpuVersion_)
1045  {
1046 #if CV_MAJOR_VERSION < 3
1047  cv::gpu::GpuMat imgGpu(image);
1048  cv::gpu::GpuMat descriptorsGPU;
1049  (*_gpuSurf.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU, true);
1050 #else
1051  cv::cuda::GpuMat imgGpu(image);
1052  cv::cuda::GpuMat descriptorsGPU;
1053  (*_gpuSurf.get())(imgGpu, cv::cuda::GpuMat(), keypoints, descriptorsGPU, true);
1054 #endif
1055 
1056  // Download descriptors
1057  if (descriptorsGPU.empty())
1058  descriptors = cv::Mat();
1059  else
1060  {
1061  UASSERT(descriptorsGPU.type() == CV_32F);
1062  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1063  descriptorsGPU.download(descriptors);
1064  }
1065  }
1066  else
1067  {
1068  _surf->compute(image, keypoints, descriptors);
1069  }
1070 #else
1071  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1072 #endif
1073 
1074  return descriptors;
1075 }
1076 
1078 //SIFT
1080 SIFT::SIFT(const ParametersMap & parameters) :
1081  nOctaveLayers_(Parameters::defaultSIFTNOctaveLayers()),
1082  contrastThreshold_(Parameters::defaultSIFTContrastThreshold()),
1083  edgeThreshold_(Parameters::defaultSIFTEdgeThreshold()),
1084  sigma_(Parameters::defaultSIFTSigma()),
1085  rootSIFT_(Parameters::defaultSIFTRootSIFT())
1086 {
1087  parseParameters(parameters);
1088 }
1089 
1091 {
1092 }
1093 
1094 void SIFT::parseParameters(const ParametersMap & parameters)
1095 {
1096  Feature2D::parseParameters(parameters);
1097 
1098  Parameters::parse(parameters, Parameters::kSIFTContrastThreshold(), contrastThreshold_);
1099  Parameters::parse(parameters, Parameters::kSIFTEdgeThreshold(), edgeThreshold_);
1100  Parameters::parse(parameters, Parameters::kSIFTNOctaveLayers(), nOctaveLayers_);
1101  Parameters::parse(parameters, Parameters::kSIFTSigma(), sigma_);
1102  Parameters::parse(parameters, Parameters::kSIFTRootSIFT(), rootSIFT_);
1103 
1104 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
1105 #ifdef RTABMAP_NONFREE
1106 #if CV_MAJOR_VERSION < 3
1107  _sift = cv::Ptr<CV_SIFT>(new CV_SIFT(this->getMaxFeatures(), nOctaveLayers_, contrastThreshold_, edgeThreshold_, sigma_));
1108 #else
1110 #endif
1111 #else
1112  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1113 #endif
1114 #else // >=4.4, >=3.4.11
1115  _sift = CV_SIFT::create(this->getMaxFeatures(), nOctaveLayers_, contrastThreshold_, edgeThreshold_, sigma_);
1116 #endif
1117 }
1118 
1119 std::vector<cv::KeyPoint> SIFT::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1120 {
1121  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1122  std::vector<cv::KeyPoint> keypoints;
1123  cv::Mat imgRoi(image, roi);
1124  cv::Mat maskRoi;
1125  if(!mask.empty())
1126  {
1127  maskRoi = cv::Mat(mask, roi);
1128  }
1129 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
1130 #ifdef RTABMAP_NONFREE
1131  _sift->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1132 #else
1133  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1134 #endif
1135 #else // >=4.4, >=3.4.11
1136  _sift->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1137 #endif
1138  return keypoints;
1139 }
1140 
1141 cv::Mat SIFT::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1142 {
1143  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1144  cv::Mat descriptors;
1145 #if CV_MAJOR_VERSION < 3 || (CV_MAJOR_VERSION == 4 && CV_MINOR_VERSION <= 3) || (CV_MAJOR_VERSION == 3 && (CV_MINOR_VERSION < 4 || (CV_MINOR_VERSION==4 && CV_SUBMINOR_VERSION<11)))
1146 #ifdef RTABMAP_NONFREE
1147  _sift->compute(image, keypoints, descriptors);
1148 #else
1149  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1150 #endif
1151 #else // >=4.4, >=3.4.11
1152  _sift->compute(image, keypoints, descriptors);
1153 #endif
1154  if( rootSIFT_ && !descriptors.empty())
1155  {
1156  UDEBUG("Performing RootSIFT...");
1157  // see http://www.pyimagesearch.com/2015/04/13/implementing-rootsift-in-python-and-opencv/
1158  // apply the Hellinger kernel by first L1-normalizing and taking the
1159  // square-root
1160  for(int i=0; i<descriptors.rows; ++i)
1161  {
1162  // By taking the L1 norm, followed by the square-root, we have
1163  // already L2 normalized the feature vector and further normalization
1164  // is not needed.
1165  descriptors.row(i) = descriptors.row(i) / cv::sum(descriptors.row(i))[0];
1166  cv::sqrt(descriptors.row(i), descriptors.row(i));
1167  }
1168  }
1169  return descriptors;
1170 }
1171 
1173 //ORB
1175 ORB::ORB(const ParametersMap & parameters) :
1176  scaleFactor_(Parameters::defaultORBScaleFactor()),
1177  nLevels_(Parameters::defaultORBNLevels()),
1178  edgeThreshold_(Parameters::defaultORBEdgeThreshold()),
1179  firstLevel_(Parameters::defaultORBFirstLevel()),
1180  WTA_K_(Parameters::defaultORBWTA_K()),
1181  scoreType_(Parameters::defaultORBScoreType()),
1182  patchSize_(Parameters::defaultORBPatchSize()),
1183  gpu_(Parameters::defaultORBGpu()),
1184  fastThreshold_(Parameters::defaultFASTThreshold()),
1185  nonmaxSuppresion_(Parameters::defaultFASTNonmaxSuppression())
1186 {
1187  parseParameters(parameters);
1188 }
1189 
1191 {
1192 }
1193 
1194 void ORB::parseParameters(const ParametersMap & parameters)
1195 {
1196  Feature2D::parseParameters(parameters);
1197 
1198  Parameters::parse(parameters, Parameters::kORBScaleFactor(), scaleFactor_);
1199  Parameters::parse(parameters, Parameters::kORBNLevels(), nLevels_);
1200  Parameters::parse(parameters, Parameters::kORBEdgeThreshold(), edgeThreshold_);
1201  Parameters::parse(parameters, Parameters::kORBFirstLevel(), firstLevel_);
1202  Parameters::parse(parameters, Parameters::kORBWTA_K(), WTA_K_);
1203  Parameters::parse(parameters, Parameters::kORBScoreType(), scoreType_);
1204  Parameters::parse(parameters, Parameters::kORBPatchSize(), patchSize_);
1205  Parameters::parse(parameters, Parameters::kORBGpu(), gpu_);
1206 
1207  Parameters::parse(parameters, Parameters::kFASTThreshold(), fastThreshold_);
1208  Parameters::parse(parameters, Parameters::kFASTNonmaxSuppression(), nonmaxSuppresion_);
1209 
1210 #if CV_MAJOR_VERSION < 3
1211 #ifdef HAVE_OPENCV_GPU
1212  if(gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1213  {
1214  UWARN("GPU version of ORB not available! Using CPU version instead...");
1215  gpu_ = false;
1216  }
1217 #else
1218  if(gpu_)
1219  {
1220  UWARN("GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1221  gpu_ = false;
1222  }
1223 #endif
1224 #else
1225 #ifndef HAVE_OPENCV_CUDAFEATURES2D
1226  if(gpu_)
1227  {
1228  UWARN("GPU version of ORB not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1229  gpu_ = false;
1230  }
1231 #endif
1232  if(gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1233  {
1234  UWARN("GPU version of ORB not available (no GPU found)! Using CPU version instead...");
1235  gpu_ = false;
1236  }
1237 #endif
1238  if(gpu_)
1239  {
1240 #if CV_MAJOR_VERSION < 3
1241 #ifdef HAVE_OPENCV_GPU
1243  _gpuOrb->setFastParams(fastThreshold_, nonmaxSuppresion_);
1244 #else
1245  UFATAL("not supposed to be here");
1246 #endif
1247 #else
1248 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1250 #endif
1251 #endif
1252  }
1253  else
1254  {
1255 #if CV_MAJOR_VERSION < 3
1256  _orb = cv::Ptr<CV_ORB>(new CV_ORB(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, scoreType_, patchSize_, parameters));
1257 #elif CV_MAJOR_VERSION > 3
1258  _orb = CV_ORB::create(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, (cv::ORB::ScoreType)scoreType_, patchSize_, fastThreshold_);
1259 #else
1260  _orb = CV_ORB::create(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, scoreType_, patchSize_, fastThreshold_);
1261 #endif
1262  }
1263 }
1264 
1265 std::vector<cv::KeyPoint> ORB::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1266 {
1267  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1268  std::vector<cv::KeyPoint> keypoints;
1269  cv::Mat imgRoi(image, roi);
1270  cv::Mat maskRoi;
1271  if(!mask.empty())
1272  {
1273  maskRoi = cv::Mat(mask, roi);
1274  }
1275 
1276  if(gpu_)
1277  {
1278 #if CV_MAJOR_VERSION < 3
1279 #ifdef HAVE_OPENCV_GPU
1280  cv::gpu::GpuMat imgGpu(imgRoi);
1281  cv::gpu::GpuMat maskGpu(maskRoi);
1282  (*_gpuOrb.obj)(imgGpu, maskGpu, keypoints);
1283 #else
1284  UERROR("Cannot use ORBGPU because OpenCV is not built with gpu module.");
1285 #endif
1286 #else
1287 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1288  cv::cuda::GpuMat d_image(imgRoi);
1289  cv::cuda::GpuMat d_mask(maskRoi);
1290  try {
1291  _gpuOrb->detectAndCompute(d_image, d_mask, keypoints, cv::cuda::GpuMat(), false);
1292  } catch (cv::Exception& e) {
1293  const char* err_msg = e.what();
1294  UWARN("OpenCV exception caught: %s", err_msg);
1295  }
1296 #endif
1297 #endif
1298  }
1299  else
1300  {
1301  _orb->detect(imgRoi, keypoints, maskRoi);
1302  }
1303 
1304  return keypoints;
1305 }
1306 
1307 cv::Mat ORB::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1308 {
1309  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1310  cv::Mat descriptors;
1311  if(image.empty())
1312  {
1313  ULOGGER_ERROR("Image is null ?!?");
1314  return descriptors;
1315  }
1316  if(gpu_)
1317  {
1318 #if CV_MAJOR_VERSION < 3
1319 #ifdef HAVE_OPENCV_GPU
1320  cv::gpu::GpuMat imgGpu(image);
1321  cv::gpu::GpuMat descriptorsGPU;
1322  (*_gpuOrb.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU);
1323  // Download descriptors
1324  if (descriptorsGPU.empty())
1325  descriptors = cv::Mat();
1326  else
1327  {
1328  UASSERT(descriptorsGPU.type() == CV_32F);
1329  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1330  descriptorsGPU.download(descriptors);
1331  }
1332 #else
1333  UERROR("GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1334 #endif
1335 #else
1336 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1337  cv::cuda::GpuMat d_image(image);
1338  cv::cuda::GpuMat d_descriptors;
1339  try {
1340  _gpuOrb->detectAndCompute(d_image, cv::cuda::GpuMat(), keypoints, d_descriptors, true);
1341  } catch (cv::Exception& e) {
1342  const char* err_msg = e.what();
1343  UWARN("OpenCV exception caught: %s", err_msg);
1344  }
1345  // Download descriptors
1346  if (d_descriptors.empty())
1347  descriptors = cv::Mat();
1348  else
1349  {
1350  UASSERT(d_descriptors.type() == CV_32F || d_descriptors.type() == CV_8U);
1351  d_descriptors.download(descriptors);
1352  }
1353 #endif
1354 #endif
1355  }
1356  else
1357  {
1358  _orb->compute(image, keypoints, descriptors);
1359  }
1360 
1361  return descriptors;
1362 }
1363 
1365 //FAST
1367 FAST::FAST(const ParametersMap & parameters) :
1368  threshold_(Parameters::defaultFASTThreshold()),
1369  nonmaxSuppression_(Parameters::defaultFASTNonmaxSuppression()),
1370  gpu_(Parameters::defaultFASTGpu()),
1371  gpuKeypointsRatio_(Parameters::defaultFASTGpuKeypointsRatio()),
1372  minThreshold_(Parameters::defaultFASTMinThreshold()),
1373  maxThreshold_(Parameters::defaultFASTMaxThreshold()),
1374  gridRows_(Parameters::defaultFASTGridRows()),
1375  gridCols_(Parameters::defaultFASTGridCols()),
1376  fastCV_(Parameters::defaultFASTCV()),
1377  fastCVinit_(false),
1378  fastCVMaxFeatures_(10000),
1379  fastCVLastImageHeight_(0)
1380 {
1381 #ifdef RTABMAP_FASTCV
1382  char sVersion[128] = { 0 };
1383  fcvGetVersion(sVersion, 128);
1384  UINFO("fastcv version = %s", sVersion);
1385  int ix;
1386  if ((ix = fcvSetOperationMode(FASTCV_OP_PERFORMANCE)))
1387  {
1388  UERROR("fcvSetOperationMode return=%d, OpenCV FAST will be used instead!", ix);
1389  fastCV_ = 0;
1390  }
1391  else
1392  {
1393  fcvMemInit();
1394 
1395  if (!(fastCVCorners_ = (uint32_t*)fcvMemAlloc(fastCVMaxFeatures_ * sizeof(uint32_t) * 2, 16)) ||
1396  !(fastCVCornerScores_ = (uint32_t*)fcvMemAlloc( fastCVMaxFeatures_ * sizeof(uint32_t), 16 )))
1397  {
1398  UERROR("could not alloc fastcv mem, using opencv fast instead!");
1399 
1400  if (fastCVCorners_)
1401  {
1402  fcvMemFree(fastCVCorners_);
1403  fastCVCorners_ = NULL;
1404  }
1405  if (fastCVCornerScores_)
1406  {
1407  fcvMemFree(fastCVCornerScores_);
1409  }
1410  }
1411  else
1412  {
1413  fastCVinit_ = true;
1414  }
1415  }
1416  #endif
1417  parseParameters(parameters);
1418 }
1419 
1421 {
1422 #ifdef RTABMAP_FASTCV
1423  if(fastCVinit_)
1424  {
1425  fcvMemDeInit();
1426 
1427  if (fastCVCorners_)
1428  fcvMemFree(fastCVCorners_);
1429  if (fastCVCornerScores_)
1430  fcvMemFree(fastCVCornerScores_);
1431  if (fastCVTempBuf_)
1432  fcvMemFree(fastCVTempBuf_);
1433  }
1434 #endif
1435 }
1436 
1437 void FAST::parseParameters(const ParametersMap & parameters)
1438 {
1439  Feature2D::parseParameters(parameters);
1440 
1441  Parameters::parse(parameters, Parameters::kFASTThreshold(), threshold_);
1442  Parameters::parse(parameters, Parameters::kFASTNonmaxSuppression(), nonmaxSuppression_);
1443  Parameters::parse(parameters, Parameters::kFASTGpu(), gpu_);
1444  Parameters::parse(parameters, Parameters::kFASTGpuKeypointsRatio(), gpuKeypointsRatio_);
1445 
1446  Parameters::parse(parameters, Parameters::kFASTMinThreshold(), minThreshold_);
1447  Parameters::parse(parameters, Parameters::kFASTMaxThreshold(), maxThreshold_);
1448  Parameters::parse(parameters, Parameters::kFASTGridRows(), gridRows_);
1449  Parameters::parse(parameters, Parameters::kFASTGridCols(), gridCols_);
1450 
1451  Parameters::parse(parameters, Parameters::kFASTCV(), fastCV_);
1452  UASSERT(fastCV_ == 0 || fastCV_ == 9 || fastCV_ == 10);
1453 
1456 
1457 #if CV_MAJOR_VERSION < 3
1458 #ifdef HAVE_OPENCV_GPU
1459  if(gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1460  {
1461  UWARN("GPU version of FAST not available! Using CPU version instead...");
1462  gpu_ = false;
1463  }
1464 #else
1465  if(gpu_)
1466  {
1467  UWARN("GPU version of FAST not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1468  gpu_ = false;
1469  }
1470 #endif
1471 #else
1472 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1473  if(gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1474  {
1475  UWARN("GPU version of FAST not available! Using CPU version instead...");
1476  gpu_ = false;
1477  }
1478 #else
1479  if(gpu_)
1480  {
1481  UWARN("GPU version of FAST not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1482  gpu_ = false;
1483  }
1484 #endif
1485 #endif
1486  if(gpu_)
1487  {
1488 #if CV_MAJOR_VERSION < 3
1489 #ifdef HAVE_OPENCV_GPU
1491 #else
1492  UFATAL("not supposed to be here!");
1493 #endif
1494 #else
1495 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1496  UFATAL("not implemented");
1497 #endif
1498 #endif
1499  }
1500  else
1501  {
1502 #if CV_MAJOR_VERSION < 3
1503  if(gridRows_ > 0 && gridCols_ > 0)
1504  {
1505  UDEBUG("grid max features = %d", this->getMaxFeatures());
1506  cv::Ptr<cv::FeatureDetector> fastAdjuster = cv::Ptr<cv::FastAdjuster>(new cv::FastAdjuster(threshold_, nonmaxSuppression_, minThreshold_, maxThreshold_));
1507  _fast = cv::Ptr<cv::FeatureDetector>(new cv::GridAdaptedFeatureDetector(fastAdjuster, this->getMaxFeatures(), gridRows_, gridCols_));
1508  }
1509  else
1510  {
1511  if(gridRows_ > 0)
1512  {
1513  UWARN("Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1514  Parameters::kFASTGridRows().c_str(), gridRows_, Parameters::kFASTGridCols().c_str());
1515  }
1516  else if(gridCols_ > 0)
1517  {
1518  UWARN("Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1519  Parameters::kFASTGridCols().c_str(), gridCols_, Parameters::kFASTGridRows().c_str());
1520  }
1521  _fast = cv::Ptr<cv::FeatureDetector>(new CV_FAST(threshold_, nonmaxSuppression_));
1522  }
1523 #else
1524  _fast = CV_FAST::create(threshold_, nonmaxSuppression_);
1525 #endif
1526  }
1527 }
1528 
1529 std::vector<cv::KeyPoint> FAST::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1530 {
1531  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1532  std::vector<cv::KeyPoint> keypoints;
1533 
1534 #ifdef RTABMAP_FASTCV
1535  if(fastCV_>0)
1536  {
1537  // Note: mask not supported, it should be the inverse of the current mask used (0=where to extract)
1538  uint32_t nCorners = 0;
1539 
1541  if (nonmaxSuppression_)
1542  {
1543  if(fastCVTempBuf_==NULL || (fastCVTempBuf_!= NULL && fastCVLastImageHeight_!= image.rows))
1544  {
1545  if (fastCVTempBuf_)
1546  {
1547  fcvMemFree(fastCVTempBuf_);
1548  fastCVTempBuf_ = NULL;
1549  }
1550  if(!(fastCVTempBuf_ = (uint32_t*)fcvMemAlloc( (3*fastCVMaxFeatures_+image.rows+1)*4, 16 )))
1551  {
1552  UERROR("could not alloc fastcv mem for temp buf (%s=true)", Parameters::kFASTNonmaxSuppression().c_str());
1554  return keypoints;
1555  }
1556  fastCVLastImageHeight_ = image.rows;
1557  }
1558  }
1559 
1560  // image.data should be 128 bits aligned
1561  UDEBUG("%dx%d (step=%d) thr=%d maxFeatures=%d", image.cols, image.rows, image.step1(), threshold_, fastCVMaxFeatures_);
1562  if(fastCV_ == 10)
1563  {
1564  fcvCornerFast10Scoreu8(image.data, image.cols, image.rows, 0, threshold_, 0, fastCVCorners_, fastCVCornerScores_, fastCVMaxFeatures_, &nCorners, nonmaxSuppression_?1:0, fastCVTempBuf_);
1565  }
1566  else
1567  {
1568  fcvCornerFast9Scoreu8_v2(image.data, image.cols, image.rows, image.step1(), threshold_, 0, fastCVCorners_, fastCVCornerScores_, fastCVMaxFeatures_, &nCorners, nonmaxSuppression_?1:0, fastCVTempBuf_);
1569  }
1570  UDEBUG("number of corners found = %d:", nCorners);
1571  keypoints.resize(nCorners);
1572  for (uint32_t i = 0; i < nCorners; i++)
1573  {
1574  keypoints[i].pt.x = fastCVCorners_[i * 2];
1575  keypoints[i].pt.y = fastCVCorners_[(i * 2) + 1];
1576  keypoints[i].size = 3;
1577  keypoints[i].response = fastCVCornerScores_[i];
1578  }
1579 
1580  if(this->getMaxFeatures() > 0)
1581  {
1582  this->limitKeypoints(keypoints, this->getMaxFeatures());
1583  }
1584  return keypoints;
1585  }
1586 #endif
1587 
1588  if(fastCV_>0)
1589  {
1590  UWARN( "RTAB-Map is not built with FastCV support. OpenCV's FAST is used instead. "
1591  "Please set %s to 0. This message will only appear once.",
1592  Parameters::kFASTCV().c_str());
1593  fastCV_ = 0;
1594  }
1595 
1596  cv::Mat imgRoi(image, roi);
1597  cv::Mat maskRoi;
1598  if(!mask.empty())
1599  {
1600  maskRoi = cv::Mat(mask, roi);
1601  }
1602  if(gpu_)
1603  {
1604 #if CV_MAJOR_VERSION < 3
1605 #ifdef HAVE_OPENCV_GPU
1606  cv::gpu::GpuMat imgGpu(imgRoi);
1607  cv::gpu::GpuMat maskGpu(maskRoi);
1608  (*_gpuFast.obj)(imgGpu, maskGpu, keypoints);
1609 #else
1610  UERROR("Cannot use FAST GPU because OpenCV is not built with gpu module.");
1611 #endif
1612 #else
1613 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1614  UFATAL("not implemented");
1615 #endif
1616 #endif
1617  }
1618  else
1619  {
1620  _fast->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1621  }
1622  return keypoints;
1623 }
1624 
1626 //FAST-BRIEF
1629  FAST(parameters),
1630  bytes_(Parameters::defaultBRIEFBytes())
1631 {
1632  parseParameters(parameters);
1633 }
1634 
1636 {
1637 }
1638 
1640 {
1641  FAST::parseParameters(parameters);
1642 
1643  Parameters::parse(parameters, Parameters::kBRIEFBytes(), bytes_);
1644 #if CV_MAJOR_VERSION < 3
1645  _brief = cv::Ptr<CV_BRIEF>(new CV_BRIEF(bytes_));
1646 #else
1647 #ifdef HAVE_OPENCV_XFEATURES2D
1648  _brief = CV_BRIEF::create(bytes_);
1649 #else
1650  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1651 #endif
1652 #endif
1653 }
1654 
1655 cv::Mat FAST_BRIEF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1656 {
1657  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1658  cv::Mat descriptors;
1659 #if CV_MAJOR_VERSION < 3
1660  _brief->compute(image, keypoints, descriptors);
1661 #else
1662 #ifdef HAVE_OPENCV_XFEATURES2D
1663  _brief->compute(image, keypoints, descriptors);
1664 #else
1665  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1666 #endif
1667 #endif
1668  return descriptors;
1669 }
1670 
1672 //FAST-FREAK
1675  FAST(parameters),
1676  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
1677  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
1678  patternScale_(Parameters::defaultFREAKPatternScale()),
1679  nOctaves_(Parameters::defaultFREAKNOctaves())
1680 {
1681  parseParameters(parameters);
1682 }
1683 
1685 {
1686 }
1687 
1689 {
1690  FAST::parseParameters(parameters);
1691 
1692  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
1693  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
1694  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
1695  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
1696 
1697 #if CV_MAJOR_VERSION < 3
1699 #else
1700 #ifdef HAVE_OPENCV_XFEATURES2D
1702 #else
1703  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1704 #endif
1705 #endif
1706 }
1707 
1708 cv::Mat FAST_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1709 {
1710  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1711  cv::Mat descriptors;
1712 #if CV_MAJOR_VERSION < 3
1713  _freak->compute(image, keypoints, descriptors);
1714 #else
1715 #ifdef HAVE_OPENCV_XFEATURES2D
1716  _freak->compute(image, keypoints, descriptors);
1717 #else
1718  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1719 #endif
1720 #endif
1721  return descriptors;
1722 }
1723 
1725 //GFTT
1727 GFTT::GFTT(const ParametersMap & parameters) :
1728  _qualityLevel(Parameters::defaultGFTTQualityLevel()),
1729  _minDistance(Parameters::defaultGFTTMinDistance()),
1730  _blockSize(Parameters::defaultGFTTBlockSize()),
1731  _useHarrisDetector(Parameters::defaultGFTTUseHarrisDetector()),
1732  _k(Parameters::defaultGFTTK())
1733 {
1734  parseParameters(parameters);
1735 }
1736 
1738 {
1739 }
1740 
1741 void GFTT::parseParameters(const ParametersMap & parameters)
1742 {
1743  Feature2D::parseParameters(parameters);
1744 
1745  Parameters::parse(parameters, Parameters::kGFTTQualityLevel(), _qualityLevel);
1746  Parameters::parse(parameters, Parameters::kGFTTMinDistance(), _minDistance);
1747  Parameters::parse(parameters, Parameters::kGFTTBlockSize(), _blockSize);
1748  Parameters::parse(parameters, Parameters::kGFTTUseHarrisDetector(), _useHarrisDetector);
1749  Parameters::parse(parameters, Parameters::kGFTTK(), _k);
1750 
1751 #if CV_MAJOR_VERSION < 3
1752  _gftt = cv::Ptr<CV_GFTT>(new CV_GFTT(this->getMaxFeatures(), _qualityLevel, _minDistance, _blockSize, _useHarrisDetector ,_k));
1753 #else
1755 #endif
1756 }
1757 
1758 std::vector<cv::KeyPoint> GFTT::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1759 {
1760  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1761  std::vector<cv::KeyPoint> keypoints;
1762  cv::Mat imgRoi(image, roi);
1763  cv::Mat maskRoi;
1764  if(!mask.empty())
1765  {
1766  maskRoi = cv::Mat(mask, roi);
1767  }
1768  _gftt->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1769  return keypoints;
1770 }
1771 
1773 //FAST-BRIEF
1776  GFTT(parameters),
1777  bytes_(Parameters::defaultBRIEFBytes())
1778 {
1779  parseParameters(parameters);
1780 }
1781 
1783 {
1784 }
1785 
1787 {
1788  GFTT::parseParameters(parameters);
1789 
1790  Parameters::parse(parameters, Parameters::kBRIEFBytes(), bytes_);
1791 #if CV_MAJOR_VERSION < 3
1792  _brief = cv::Ptr<CV_BRIEF>(new CV_BRIEF(bytes_));
1793 #else
1794 #ifdef HAVE_OPENCV_XFEATURES2D
1795  _brief = CV_BRIEF::create(bytes_);
1796 #else
1797  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1798 #endif
1799 #endif
1800 }
1801 
1802 cv::Mat GFTT_BRIEF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1803 {
1804  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1805  cv::Mat descriptors;
1806 #if CV_MAJOR_VERSION < 3
1807  _brief->compute(image, keypoints, descriptors);
1808 #else
1809 #ifdef HAVE_OPENCV_XFEATURES2D
1810  _brief->compute(image, keypoints, descriptors);
1811 #else
1812  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1813 #endif
1814 #endif
1815  return descriptors;
1816 }
1817 
1819 //GFTT-FREAK
1822  GFTT(parameters),
1823  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
1824  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
1825  patternScale_(Parameters::defaultFREAKPatternScale()),
1826  nOctaves_(Parameters::defaultFREAKNOctaves())
1827 {
1828  parseParameters(parameters);
1829 }
1830 
1832 {
1833 }
1834 
1836 {
1837  GFTT::parseParameters(parameters);
1838 
1839  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
1840  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
1841  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
1842  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
1843 
1844 #if CV_MAJOR_VERSION < 3
1846 #else
1847 #ifdef HAVE_OPENCV_XFEATURES2D
1849 #else
1850  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1851 #endif
1852 #endif
1853 }
1854 
1855 cv::Mat GFTT_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1856 {
1857  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1858  cv::Mat descriptors;
1859 #if CV_MAJOR_VERSION < 3
1860  _freak->compute(image, keypoints, descriptors);
1861 #else
1862 #ifdef HAVE_OPENCV_XFEATURES2D
1863  _freak->compute(image, keypoints, descriptors);
1864 #else
1865  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1866 #endif
1867 #endif
1868  return descriptors;
1869 }
1870 
1872 //SURF-FREAK
1875  SURF(parameters),
1876  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
1877  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
1878  patternScale_(Parameters::defaultFREAKPatternScale()),
1879  nOctaves_(Parameters::defaultFREAKNOctaves())
1880 {
1881  parseParameters(parameters);
1882 }
1883 
1885 {
1886 }
1887 
1889 {
1890  SURF::parseParameters(parameters);
1891 
1892  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
1893  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
1894  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
1895  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
1896 
1897 #if CV_MAJOR_VERSION < 3
1899 #else
1900 #ifdef HAVE_OPENCV_XFEATURES2D
1902 #else
1903  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1904 #endif
1905 #endif
1906 }
1907 
1908 cv::Mat SURF_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1909 {
1910  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1911  cv::Mat descriptors;
1912 #if CV_MAJOR_VERSION < 3
1913  _freak->compute(image, keypoints, descriptors);
1914 #else
1915 #ifdef HAVE_OPENCV_XFEATURES2D
1916  _freak->compute(image, keypoints, descriptors);
1917 #else
1918  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
1919 #endif
1920 #endif
1921  return descriptors;
1922 }
1923 
1925 //GFTT-ORB
1927 GFTT_ORB::GFTT_ORB(const ParametersMap & parameters) :
1928  GFTT(parameters),
1929  _orb(parameters)
1930 {
1931  parseParameters(parameters);
1932 }
1933 
1935 {
1936 }
1937 
1939 {
1940  GFTT::parseParameters(parameters);
1941  _orb.parseParameters(parameters);
1942 }
1943 
1944 cv::Mat GFTT_ORB::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1945 {
1946  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1947  return _orb.generateDescriptors(image, keypoints);
1948 }
1949 
1951 //BRISK
1953 BRISK::BRISK(const ParametersMap & parameters) :
1954  thresh_(Parameters::defaultBRISKThresh()),
1955  octaves_(Parameters::defaultBRISKOctaves()),
1956  patternScale_(Parameters::defaultBRISKPatternScale())
1957 {
1958  parseParameters(parameters);
1959 }
1960 
1962 {
1963 }
1964 
1965 void BRISK::parseParameters(const ParametersMap & parameters)
1966 {
1967  Feature2D::parseParameters(parameters);
1968 
1969  Parameters::parse(parameters, Parameters::kBRISKThresh(), thresh_);
1970  Parameters::parse(parameters, Parameters::kBRISKOctaves(), octaves_);
1971  Parameters::parse(parameters, Parameters::kBRISKPatternScale(), patternScale_);
1972 
1973 #if CV_MAJOR_VERSION < 3
1974  brisk_ = cv::Ptr<CV_BRISK>(new CV_BRISK(thresh_, octaves_, patternScale_));
1975 #else
1976  brisk_ = CV_BRISK::create(thresh_, octaves_, patternScale_);
1977 #endif
1978 }
1979 
1980 std::vector<cv::KeyPoint> BRISK::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1981 {
1982  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1983  std::vector<cv::KeyPoint> keypoints;
1984  cv::Mat imgRoi(image, roi);
1985  cv::Mat maskRoi;
1986  if(!mask.empty())
1987  {
1988  maskRoi = cv::Mat(mask, roi);
1989  }
1990  brisk_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1991  return keypoints;
1992 }
1993 
1994 cv::Mat BRISK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1995 {
1996  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1997  cv::Mat descriptors;
1998  brisk_->compute(image, keypoints, descriptors);
1999  return descriptors;
2000 }
2001 
2003 //KAZE
2005 KAZE::KAZE(const ParametersMap & parameters) :
2006  extended_(Parameters::defaultKAZEExtended()),
2007  upright_(Parameters::defaultKAZEUpright()),
2008  threshold_(Parameters::defaultKAZEThreshold()),
2009  nOctaves_(Parameters::defaultKAZENOctaves()),
2010  nOctaveLayers_(Parameters::defaultKAZENOctaveLayers()),
2011  diffusivity_(Parameters::defaultKAZEDiffusivity())
2012 {
2013  parseParameters(parameters);
2014 }
2015 
2017 {
2018 }
2019 
2020 void KAZE::parseParameters(const ParametersMap & parameters)
2021 {
2022  Feature2D::parseParameters(parameters);
2023 
2024  Parameters::parse(parameters, Parameters::kKAZEExtended(), extended_);
2025  Parameters::parse(parameters, Parameters::kKAZEUpright(), upright_);
2026  Parameters::parse(parameters, Parameters::kKAZEThreshold(), threshold_);
2027  Parameters::parse(parameters, Parameters::kKAZENOctaves(), nOctaves_);
2028  Parameters::parse(parameters, Parameters::kKAZENOctaveLayers(), nOctaveLayers_);
2029  Parameters::parse(parameters, Parameters::kKAZEDiffusivity(), diffusivity_);
2030 
2031 #if CV_MAJOR_VERSION > 3
2032  kaze_ = cv::KAZE::create(extended_, upright_, threshold_, nOctaves_, nOctaveLayers_, (cv::KAZE::DiffusivityType)diffusivity_);
2033 #elif CV_MAJOR_VERSION > 2
2034  kaze_ = cv::KAZE::create(extended_, upright_, threshold_, nOctaves_, nOctaveLayers_, diffusivity_);
2035 #else
2036  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2037 #endif
2038 }
2039 
2040 std::vector<cv::KeyPoint> KAZE::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2041 {
2042  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2043  std::vector<cv::KeyPoint> keypoints;
2044 #if CV_MAJOR_VERSION > 2
2045  cv::Mat imgRoi(image, roi);
2046  cv::Mat maskRoi;
2047  if (!mask.empty())
2048  {
2049  maskRoi = cv::Mat(mask, roi);
2050  }
2051  kaze_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
2052 #else
2053  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2054 #endif
2055  return keypoints;
2056 }
2057 
2058 cv::Mat KAZE::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2059 {
2060  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2061  cv::Mat descriptors;
2062 #if CV_MAJOR_VERSION > 2
2063  kaze_->compute(image, keypoints, descriptors);
2064 #else
2065  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2066 #endif
2067  return descriptors;
2068 }
2069 
2071 //ORBOctree
2074  scaleFactor_(Parameters::defaultORBScaleFactor()),
2075  nLevels_(Parameters::defaultORBNLevels()),
2076  patchSize_(Parameters::defaultORBPatchSize()),
2077  edgeThreshold_(Parameters::defaultORBEdgeThreshold()),
2078  fastThreshold_(Parameters::defaultFASTThreshold()),
2079  fastMinThreshold_(Parameters::defaultFASTMinThreshold())
2080 {
2081  parseParameters(parameters);
2082 }
2083 
2085 {
2086 }
2087 
2089 {
2090  Feature2D::parseParameters(parameters);
2091 
2092  Parameters::parse(parameters, Parameters::kORBScaleFactor(), scaleFactor_);
2093  Parameters::parse(parameters, Parameters::kORBNLevels(), nLevels_);
2094  Parameters::parse(parameters, Parameters::kORBPatchSize(), patchSize_);
2095  Parameters::parse(parameters, Parameters::kORBEdgeThreshold(), edgeThreshold_);
2096 
2097  Parameters::parse(parameters, Parameters::kFASTThreshold(), fastThreshold_);
2098  Parameters::parse(parameters, Parameters::kFASTMinThreshold(), fastMinThreshold_);
2099 
2100 #ifdef RTABMAP_ORB_OCTREE
2102 #else
2103  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2104 #endif
2105 }
2106 
2107 std::vector<cv::KeyPoint> ORBOctree::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2108 {
2109  std::vector<cv::KeyPoint> keypoints;
2110  descriptors_ = cv::Mat();
2111 #ifdef RTABMAP_ORB_OCTREE
2112  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2113  cv::Mat imgRoi(image, roi);
2114  cv::Mat maskRoi;
2115  if(!mask.empty())
2116  {
2117  maskRoi = cv::Mat(mask, roi);
2118  }
2119 
2120  (*_orb)(imgRoi, maskRoi, keypoints, descriptors_);
2121 
2122  if((int)keypoints.size() > this->getMaxFeatures())
2123  {
2124  limitKeypoints(keypoints, descriptors_, this->getMaxFeatures());
2125  }
2126 #else
2127  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2128 #endif
2129  return keypoints;
2130 }
2131 
2132 cv::Mat ORBOctree::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2133 {
2134 #ifdef RTABMAP_ORB_OCTREE
2135  UASSERT_MSG((int)keypoints.size() == descriptors_.rows, uFormat("keypoints=%d descriptors=%d", (int)keypoints.size(), descriptors_.rows).c_str());
2136 #else
2137  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2138 #endif
2139  return descriptors_;
2140 }
2141 
2143 //SuperPointTorch
2146  path_(Parameters::defaultSuperPointModelPath()),
2147  threshold_(Parameters::defaultSuperPointThreshold()),
2148  nms_(Parameters::defaultSuperPointNMS()),
2149  minDistance_(Parameters::defaultSuperPointNMSRadius()),
2150  cuda_(Parameters::defaultSuperPointCuda())
2151 {
2152  parseParameters(parameters);
2153 }
2154 
2156 {
2157 }
2158 
2160 {
2161  Feature2D::parseParameters(parameters);
2162 
2163  std::string previousPath = path_;
2164 #ifdef RTABMAP_TORCH
2165  bool previousCuda = cuda_;
2166 #endif
2167  Parameters::parse(parameters, Parameters::kSuperPointModelPath(), path_);
2168  Parameters::parse(parameters, Parameters::kSuperPointThreshold(), threshold_);
2169  Parameters::parse(parameters, Parameters::kSuperPointNMS(), nms_);
2170  Parameters::parse(parameters, Parameters::kSuperPointNMSRadius(), minDistance_);
2171  Parameters::parse(parameters, Parameters::kSuperPointCuda(), cuda_);
2172 
2173 #ifdef RTABMAP_TORCH
2174  if(superPoint_.get() == 0 || path_.compare(previousPath) != 0 || previousCuda != cuda_)
2175  {
2176  superPoint_ = cv::Ptr<SPDetector>(new SPDetector(path_, threshold_, nms_, minDistance_, cuda_));
2177  }
2178  else
2179  {
2180  superPoint_->setThreshold(threshold_);
2181  superPoint_->SetNMS(nms_);
2182  superPoint_->setMinDistance(minDistance_);
2183  }
2184 #else
2185  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2186 #endif
2187 }
2188 
2189 std::vector<cv::KeyPoint> SuperPointTorch::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2190 {
2191 #ifdef RTABMAP_TORCH
2192  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2193  if(roi.x!=0 || roi.y !=0)
2194  {
2195  UERROR("SuperPoint: Not supporting ROI (%d,%d,%d,%d). Make sure %s, %s, %s, %s, %s, %s are all set to default values.",
2196  roi.x, roi.y, roi.width, roi.height,
2197  Parameters::kKpRoiRatios().c_str(),
2198  Parameters::kVisRoiRatios().c_str(),
2199  Parameters::kVisGridRows().c_str(),
2200  Parameters::kVisGridCols().c_str(),
2201  Parameters::kKpGridRows().c_str(),
2202  Parameters::kKpGridCols().c_str());
2203  return std::vector<cv::KeyPoint>();
2204  }
2205  return superPoint_->detect(image, mask);
2206 #else
2207  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2208  return std::vector<cv::KeyPoint>();
2209 #endif
2210 }
2211 
2212 cv::Mat SuperPointTorch::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2213 {
2214 #ifdef RTABMAP_TORCH
2215  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2216  return superPoint_->compute(keypoints);
2217 #else
2218  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2219  return cv::Mat();
2220 #endif
2221 }
2222 
2223 
2225 //GFTT-DAISY
2228  GFTT(parameters),
2229  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2230  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2231  patternScale_(Parameters::defaultFREAKPatternScale()),
2232  nOctaves_(Parameters::defaultFREAKNOctaves())
2233 {
2234  parseParameters(parameters);
2235 }
2236 
2238 {
2239 }
2240 
2242 {
2243  GFTT::parseParameters(parameters);
2244 
2245  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2246  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2247  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2248  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2249 
2250 #ifdef HAVE_OPENCV_XFEATURES2D
2251  _daisy = CV_DAISY::create();
2252 #else
2253  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2254 #endif
2255 }
2256 
2257 cv::Mat GFTT_DAISY::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2258 {
2259  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2260  cv::Mat descriptors;
2261 #ifdef HAVE_OPENCV_XFEATURES2D
2262  _daisy->compute(image, keypoints, descriptors);
2263 #else
2264  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2265 #endif
2266  return descriptors;
2267 }
2268 
2270 //SURF-DAISY
2273  SURF(parameters),
2274  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2275  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2276  patternScale_(Parameters::defaultFREAKPatternScale()),
2277  nOctaves_(Parameters::defaultFREAKNOctaves())
2278 {
2279  parseParameters(parameters);
2280 }
2281 
2283 {
2284 }
2285 
2287 {
2288  SURF::parseParameters(parameters);
2289 
2290  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2291  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2292  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2293  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2294 
2295 #ifdef HAVE_OPENCV_XFEATURES2D
2296  _daisy = CV_DAISY::create();
2297 #else
2298  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2299 #endif
2300 }
2301 
2302 cv::Mat SURF_DAISY::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2303 {
2304  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2305  cv::Mat descriptors;
2306 #ifdef HAVE_OPENCV_XFEATURES2D
2307  _daisy->compute(image, keypoints, descriptors);
2308 #else
2309  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2310 #endif
2311  return descriptors;
2312 }
2313 
2314 }
d
GLM_FUNC_DECL genIType mask(genIType const &count)
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
bool RTABMAP_EXP isFinite(const cv::Point3f &pt)
Definition: util3d.cpp:3194
#define NULL
int fastCVLastImageHeight_
Definition: Features2d.h:358
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:497
virtual ~BRISK()
float maxDisparity() const
Definition: Stereo.h:57
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const =0
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
int nOctaveLayers_
Definition: Features2d.h:551
virtual void parseParameters(const ParametersMap &parameters)
virtual std::vector< cv::Point2f > computeCorrespondences(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, std::vector< unsigned char > &status) const
Definition: Stereo.cpp:72
Definition: UTimer.h:46
static void limitKeypoints(std::vector< cv::KeyPoint > &keypoints, int maxKeypoints)
Definition: Features2d.cpp:271
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual ~SIFT()
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
double gpuKeypointsRatio_
Definition: Features2d.h:349
FAST_BRIEF(const ParametersMap &parameters=ParametersMap())
GFTT_DAISY(const ParametersMap &parameters=ParametersMap())
virtual void parseParameters(const ParametersMap &parameters)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
f
x
SURF_DAISY(const ParametersMap &parameters=ParametersMap())
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:451
double _qualityLevel
Definition: Features2d.h:421
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:405
GFTT_FREAK(const ParametersMap &parameters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
cv::SIFT CV_SIFT
Definition: Features2d.h:50
double edgeThreshold_
Definition: Features2d.h:293
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
uint32_t * fastCVCornerScores_
Definition: Features2d.h:360
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:962
void * fastCVTempBuf_
Definition: Features2d.h:361
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
cv::Ptr< CV_ORB > _orb
Definition: Features2d.h:327
virtual void parseParameters(const ParametersMap &parameters)
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:468
float scaleFactor_
Definition: Features2d.h:315
const cv::Mat & depthOrRightRaw() const
Definition: SensorData.h:184
cv::BriefDescriptorExtractor CV_BRIEF
Definition: Features2d.h:55
cv::Ptr< ORBextractor > _orb
Definition: Features2d.h:581
GLM_FUNC_DECL genType e()
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
virtual ~SURF()
Definition: Features2d.cpp:958
float UTILITE_EXP uStr2Float(const std::string &str)
uint32_t * fastCVCorners_
Definition: Features2d.h:359
const std::vector< StereoCameraModel > & stereoCameraModels() const
Definition: SensorData.h:237
bool nonmaxSuppression_
Definition: Features2d.h:347
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
double contrastThreshold_
Definition: Features2d.h:292
std::vector< float > _roiRatios
Definition: Features2d.h:239
int nOctaveLayers_
Definition: Features2d.h:291
Basic mathematics functions.
cv::Ptr< CV_BRISK > brisk_
Definition: Features2d.h:529
cv::Ptr< CV_ORB_GPU > _gpuOrb
Definition: Features2d.h:328
Some conversion functions.
cv::FastFeatureDetector CV_FAST
Definition: Features2d.h:52
virtual ~Feature2D()
Definition: Features2d.cpp:447
Feature2D(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:433
detail::uint16 uint16_t
Definition: fwd.hpp:912
std::vector< cv::KeyPoint > generateKeypoints(const cv::Mat &image, const cv::Mat &mask=cv::Mat())
Definition: Features2d.cpp:670
#define UFATAL(...)
cv::SURF CV_SURF
Definition: Features2d.h:51
SuperPointTorch(const ParametersMap &parameters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
cv::Mat rightRaw() const
Definition: SensorData.h:211
bool uIsFinite(const T &value)
Definition: UMath.h:55
cv::Ptr< CV_FAST_GPU > _gpuFast
Definition: Features2d.h:364
#define UASSERT(condition)
std::vector< cv::Point3f > generateKeypoints3D(const SensorData &data, const std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:788
virtual void parseParameters(const ParametersMap &parameters)
virtual ~ORB()
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:566
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
static void filterKeypointsByDisparity(std::vector< cv::KeyPoint > &keypoints, const cv::Mat &disparity, float minDisparity)
Definition: Features2d.cpp:204
BRISK(const ParametersMap &parameters=ParametersMap())
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:236
cv::BRISK CV_BRISK
Definition: Features2d.h:56
cv::Ptr< SPDetector > superPoint_
Definition: Features2d.h:599
virtual ~FAST()
static Feature2D * create(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:511
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
virtual void parseParameters(const ParametersMap &parameters)
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
cv::Mat depthRaw() const
Definition: SensorData.h:210
virtual ~GFTT()
const cv::Mat & imageRaw() const
Definition: SensorData.h:183
virtual void parseParameters(const ParametersMap &parameters)
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:490
SURF_FREAK(const ParametersMap &parameters=ParametersMap())
cv::Rect RTABMAP_EXP computeRoi(const cv::Mat &image, const std::string &roiRatios)
Definition: util2d.cpp:1113
FAST(const ParametersMap &parameters=ParametersMap())
virtual void parseParameters(const ParametersMap &parameters)
virtual void parseParameters(const ParametersMap &parameters)
Definition: Stereo.cpp:61
virtual void parseParameters(const ParametersMap &parameters)
static void filterKeypointsByDepth(std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, float minDepth, float maxDepth)
Definition: Features2d.cpp:85
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
virtual void parseParameters(const ParametersMap &parameters)
KAZE(const ParametersMap &parameters=ParametersMap())
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
cv::gpu::SURF_GPU CV_SURF_GPU
Definition: Features2d.h:57
static ULogger::Level level()
Definition: ULogger.h:340
int fastThreshold_
Definition: Features2d.h:324
float patternScale_
Definition: Features2d.h:527
static cv::Rect computeRoi(const cv::Mat &image, const std::string &roiRatios)
Definition: Features2d.cpp:420
SIFT(const ParametersMap &parameters=ParametersMap())
static Stereo * create(const ParametersMap &parameters=ParametersMap())
Definition: Stereo.cpp:35
double sigma_
Definition: Features2d.h:294
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:383
detail::uint32 uint32_t
Definition: fwd.hpp:916
#define false
Definition: ConvertUTF.c:56
cv::Mat descriptors_
Definition: Features2d.h:582
cv::Ptr< CV_SURF > _surf
Definition: Features2d.h:272
virtual ~KAZE()
FAST_FREAK(const ParametersMap &parameters=ParametersMap())
int nOctaveLayers_
Definition: Features2d.h:266
float gpuKeypointsRatio_
Definition: Features2d.h:269
cv::Mat generateDescriptors(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:772
cv::FREAK CV_FREAK
Definition: Features2d.h:53
#define UDEBUG(...)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
virtual void parseParameters(const ParametersMap &parameters)
ORBOctree(const ParametersMap &parameters=ParametersMap())
ORB(const ParametersMap &parameters=ParametersMap())
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:446
cv::Ptr< CV_SIFT > _sift
Definition: Features2d.h:297
#define UERROR(...)
virtual void parseParameters(const ParametersMap &parameters)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual void parseParameters(const ParametersMap &parameters)
GFTT(const ParametersMap &parameters=ParametersMap())
int fastCVMaxFeatures_
Definition: Features2d.h:357
float threshold_
Definition: Features2d.h:549
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
ULogger class and convenient macros.
SURF(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:946
#define UWARN(...)
bool fastCVinit_
Definition: Features2d.h:356
virtual void parseParameters(const ParametersMap &parameters)
double ticks()
Definition: UTimer.cpp:117
double _minDistance
Definition: Features2d.h:422
bool gpuVersion_
Definition: Features2d.h:270
GFTT_BRIEF(const ParametersMap &parameters=ParametersMap())
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
int edgeThreshold_
Definition: Features2d.h:317
cv::gpu::ORB_GPU CV_ORB_GPU
Definition: Features2d.h:58
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())=0
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
virtual void parseParameters(const ParametersMap &parameters)
GFTT_ORB(const ParametersMap &parameters=ParametersMap())
cv::GFTTDetector CV_GFTT
Definition: Features2d.h:54
cv::gpu::FAST_GPU CV_FAST_GPU
Definition: Features2d.h:59
int getMaxFeatures() const
Definition: Features2d.h:204
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
virtual std::vector< cv::KeyPoint > generateKeypointsImpl(const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
bool nonmaxSuppresion_
Definition: Features2d.h:325
std::vector< cv::Point3f > RTABMAP_EXP generateKeypoints3DDepth(const std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, const CameraModel &cameraModel, float minDepth=0, float maxDepth=0)
cv::Ptr< cv::FeatureDetector > _fast
Definition: Features2d.h:363
double hessianThreshold_
Definition: Features2d.h:264
std::string UTILITE_EXP uFormat(const char *fmt,...)
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
cv::Ptr< CV_GFTT > _gftt
Definition: Features2d.h:427
ParametersMap parameters_
Definition: Features2d.h:235
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
Definition: UStl.h:443
virtual void parseParameters(const ParametersMap &parameters)
virtual void parseParameters(const ParametersMap &parameters)
std::vector< cv::Point3f > RTABMAP_EXP generateKeypoints3DStereo(const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const StereoCameraModel &model, const std::vector< unsigned char > &mask=std::vector< unsigned char >(), float minDepth=0, float maxDepth=0)
bool _useHarrisDetector
Definition: Features2d.h:424
cv::Ptr< CV_SURF_GPU > _gpuSurf
Definition: Features2d.h:273
#define UINFO(...)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28