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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:27