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 #ifdef HAVE_OPENCV_CUDAIMGPROC
79 #include <opencv2/cudaimgproc.hpp>
80 #endif
81 
82 #ifdef RTABMAP_FASTCV
83 #include <fastcv.h>
84 #endif
85 
86 #ifdef RTABMAP_CUDASIFT
87 #include <cudasift/cudaImage.h>
88 #include <cudasift/cudaSift.h>
89 #endif
90 namespace rtabmap {
91 
93  std::vector<cv::KeyPoint> & keypoints,
94  const cv::Mat & depth,
95  float minDepth,
96  float maxDepth)
97 {
98  cv::Mat descriptors;
99  filterKeypointsByDepth(keypoints, descriptors, depth, minDepth, maxDepth);
100 }
101 
103  std::vector<cv::KeyPoint> & keypoints,
104  cv::Mat & descriptors,
105  const cv::Mat & depth,
106  float minDepth,
107  float maxDepth)
108 {
109  UASSERT(minDepth >= 0.0f);
110  UASSERT(maxDepth <= 0.0f || maxDepth > minDepth);
111  if(!depth.empty() && (descriptors.empty() || descriptors.rows == (int)keypoints.size()))
112  {
113  std::vector<cv::KeyPoint> output(keypoints.size());
114  std::vector<int> indexes(keypoints.size(), 0);
115  int oi=0;
116  bool isInMM = depth.type() == CV_16UC1;
117  for(unsigned int i=0; i<keypoints.size(); ++i)
118  {
119  int u = int(keypoints[i].pt.x+0.5f);
120  int v = int(keypoints[i].pt.y+0.5f);
121  if(u >=0 && u<depth.cols && v >=0 && v<depth.rows)
122  {
123  float d = isInMM?(float)depth.at<uint16_t>(v,u)*0.001f:depth.at<float>(v,u);
124  if(uIsFinite(d) && d>minDepth && (maxDepth <= 0.0f || d < maxDepth))
125  {
126  output[oi++] = keypoints[i];
127  indexes[i] = 1;
128  }
129  }
130  }
131  output.resize(oi);
132  keypoints = output;
133 
134  if(!descriptors.empty() && (int)keypoints.size() != descriptors.rows)
135  {
136  if(keypoints.size() == 0)
137  {
138  descriptors = cv::Mat();
139  }
140  else
141  {
142  cv::Mat newDescriptors((int)keypoints.size(), descriptors.cols, descriptors.type());
143  int di = 0;
144  for(unsigned int i=0; i<indexes.size(); ++i)
145  {
146  if(indexes[i] == 1)
147  {
148  if(descriptors.type() == CV_32FC1)
149  {
150  memcpy(newDescriptors.ptr<float>(di++), descriptors.ptr<float>(i), descriptors.cols*sizeof(float));
151  }
152  else // CV_8UC1
153  {
154  memcpy(newDescriptors.ptr<char>(di++), descriptors.ptr<char>(i), descriptors.cols*sizeof(char));
155  }
156  }
157  }
158  descriptors = newDescriptors;
159  }
160  }
161  }
162 }
163 
165  std::vector<cv::KeyPoint> & keypoints,
166  cv::Mat & descriptors,
167  std::vector<cv::Point3f> & keypoints3D,
168  float minDepth,
169  float maxDepth)
170 {
171  UDEBUG("");
172  //remove all keypoints/descriptors with no valid 3D points
173  UASSERT(((int)keypoints.size() == descriptors.rows || descriptors.empty()) &&
174  keypoints3D.size() == keypoints.size());
175  std::vector<cv::KeyPoint> validKeypoints(keypoints.size());
176  std::vector<cv::Point3f> validKeypoints3D(keypoints.size());
177  cv::Mat validDescriptors(descriptors.size(), descriptors.type());
178 
179  int oi=0;
180  float minDepthSqr = minDepth * minDepth;
181  float maxDepthSqr = maxDepth * maxDepth;
182  for(unsigned int i=0; i<keypoints3D.size(); ++i)
183  {
184  cv::Point3f & pt = keypoints3D[i];
185  if(util3d::isFinite(pt))
186  {
187  float distSqr = pt.x*pt.x+pt.y*pt.y+pt.z*pt.z;
188  if(distSqr >= minDepthSqr && (maxDepthSqr==0.0f || distSqr <= maxDepthSqr))
189  {
190  validKeypoints[oi] = keypoints[i];
191  validKeypoints3D[oi] = pt;
192  if(!descriptors.empty())
193  {
194  descriptors.row(i).copyTo(validDescriptors.row(oi));
195  }
196  ++oi;
197  }
198  }
199  }
200  UDEBUG("Removed %d invalid 3D points", (int)keypoints3D.size()-oi);
201  validKeypoints.resize(oi);
202  validKeypoints3D.resize(oi);
203  keypoints = validKeypoints;
204  keypoints3D = validKeypoints3D;
205  if(!descriptors.empty())
206  {
207  descriptors = validDescriptors.rowRange(0, oi).clone();
208  }
209 }
210 
212  std::vector<cv::KeyPoint> & keypoints,
213  const cv::Mat & disparity,
214  float minDisparity)
215 {
216  cv::Mat descriptors;
217  filterKeypointsByDisparity(keypoints, descriptors, disparity, minDisparity);
218 }
219 
221  std::vector<cv::KeyPoint> & keypoints,
222  cv::Mat & descriptors,
223  const cv::Mat & disparity,
224  float minDisparity)
225 {
226  if(!disparity.empty() && minDisparity > 0.0f && (descriptors.empty() || descriptors.rows == (int)keypoints.size()))
227  {
228  std::vector<cv::KeyPoint> output(keypoints.size());
229  std::vector<int> indexes(keypoints.size(), 0);
230  int oi=0;
231  for(unsigned int i=0; i<keypoints.size(); ++i)
232  {
233  int u = int(keypoints[i].pt.x+0.5f);
234  int v = int(keypoints[i].pt.y+0.5f);
235  if(u >=0 && u<disparity.cols && v >=0 && v<disparity.rows)
236  {
237  float d = disparity.type() == CV_16SC1?float(disparity.at<short>(v,u))/16.0f:disparity.at<float>(v,u);
238  if(d!=0.0f && uIsFinite(d) && d >= minDisparity)
239  {
240  output[oi++] = keypoints[i];
241  indexes[i] = 1;
242  }
243  }
244  }
245  output.resize(oi);
246  keypoints = output;
247 
248  if(!descriptors.empty() && (int)keypoints.size() != descriptors.rows)
249  {
250  if(keypoints.size() == 0)
251  {
252  descriptors = cv::Mat();
253  }
254  else
255  {
256  cv::Mat newDescriptors((int)keypoints.size(), descriptors.cols, descriptors.type());
257  int di = 0;
258  for(unsigned int i=0; i<indexes.size(); ++i)
259  {
260  if(indexes[i] == 1)
261  {
262  if(descriptors.type() == CV_32FC1)
263  {
264  memcpy(newDescriptors.ptr<float>(di++), descriptors.ptr<float>(i), descriptors.cols*sizeof(float));
265  }
266  else // CV_8UC1
267  {
268  memcpy(newDescriptors.ptr<char>(di++), descriptors.ptr<char>(i), descriptors.cols*sizeof(char));
269  }
270  }
271  }
272  descriptors = newDescriptors;
273  }
274  }
275  }
276 }
277 
278 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, int maxKeypoints, const cv::Size & imageSize, bool ssc)
279 {
280  cv::Mat descriptors;
281  limitKeypoints(keypoints, descriptors, maxKeypoints, imageSize, ssc);
282 }
283 
284 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, cv::Mat & descriptors, int maxKeypoints, const cv::Size & imageSize, bool ssc)
285 {
286  std::vector<cv::Point3f> keypoints3D;
287  limitKeypoints(keypoints, keypoints3D, descriptors, maxKeypoints, imageSize, ssc);
288 }
289 
290 void Feature2D::limitKeypoints(std::vector<cv::KeyPoint> & keypoints, std::vector<cv::Point3f> & keypoints3D, cv::Mat & descriptors, int maxKeypoints, const cv::Size & imageSize, bool ssc)
291 {
292  UASSERT_MSG((int)keypoints.size() == descriptors.rows || descriptors.rows == 0, uFormat("keypoints=%d descriptors=%d", (int)keypoints.size(), descriptors.rows).c_str());
293  UASSERT_MSG(keypoints.size() == keypoints3D.size() || keypoints3D.size() == 0, uFormat("keypoints=%d keypoints3D=%d", (int)keypoints.size(), (int)keypoints3D.size()).c_str());
294  if(maxKeypoints > 0 && (int)keypoints.size() > maxKeypoints)
295  {
296  UTimer timer;
297  int removed;
298  std::vector<cv::KeyPoint> kptsTmp;
299  std::vector<cv::Point3f> kpts3DTmp;
300  cv::Mat descriptorsTmp;
301  if(ssc)
302  {
303  ULOGGER_DEBUG("too much words (%d), removing words with SSC", keypoints.size());
304 
305  // Sorting keypoints by deacreasing order of strength
306  std::vector<float> responseVector;
307  for (unsigned int i = 0; i < keypoints.size(); i++)
308  {
309  responseVector.push_back(keypoints[i].response);
310  }
311  std::vector<int> indx(responseVector.size());
312  std::iota(std::begin(indx), std::end(indx), 0);
313 
314 #if CV_MAJOR_VERSION >= 4
315  cv::sortIdx(responseVector, indx, cv::SORT_DESCENDING);
316 #else
317  cv::sortIdx(responseVector, indx, CV_SORT_DESCENDING);
318 #endif
319 
320  static constexpr float tolerance = 0.1;
321  auto ResultVec = util2d::SSC(keypoints, maxKeypoints, tolerance, imageSize.width, imageSize.height, indx);
322  removed = keypoints.size()-ResultVec.size();
323  // retrieve final keypoints
324  kptsTmp.resize(ResultVec.size());
325  if(!keypoints3D.empty())
326  {
327  kpts3DTmp.resize(ResultVec.size());
328  }
329  if(descriptors.rows)
330  {
331  descriptorsTmp = cv::Mat(ResultVec.size(), descriptors.cols, descriptors.type());
332  }
333  for(unsigned int k=0; k<ResultVec.size(); ++k)
334  {
335  kptsTmp[k] = keypoints[ResultVec[k]];
336  if(keypoints3D.size())
337  {
338  kpts3DTmp[k] = keypoints3D[ResultVec[k]];
339  }
340  if(descriptors.rows)
341  {
342  if(descriptors.type() == CV_32FC1)
343  {
344  memcpy(descriptorsTmp.ptr<float>(k), descriptors.ptr<float>(ResultVec[k]), descriptors.cols*sizeof(float));
345  }
346  else
347  {
348  memcpy(descriptorsTmp.ptr<char>(k), descriptors.ptr<char>(ResultVec[k]), descriptors.cols*sizeof(char));
349  }
350  }
351  }
352  }
353  else
354  {
355  ULOGGER_DEBUG("too many words (%d), removing words with the hessian threshold", keypoints.size());
356  // Remove words under the new hessian threshold
357 
358  // Sort words by hessian
359  std::multimap<float, int> hessianMap; // <hessian,id>
360  for(unsigned int i = 0; i <keypoints.size(); ++i)
361  {
362  //Keep track of the data, to be easier to manage the data in the next step
363  hessianMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
364  }
365 
366  // Remove them from the signature
367  removed = (int)hessianMap.size()-maxKeypoints;
368  std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
369  kptsTmp.resize(maxKeypoints);
370  if(!keypoints3D.empty())
371  {
372  kpts3DTmp.resize(maxKeypoints);
373  }
374  if(descriptors.rows)
375  {
376  descriptorsTmp = cv::Mat(maxKeypoints, descriptors.cols, descriptors.type());
377  }
378  for(unsigned int k=0; k<kptsTmp.size() && iter!=hessianMap.rend(); ++k, ++iter)
379  {
380  kptsTmp[k] = keypoints[iter->second];
381  if(keypoints3D.size())
382  {
383  kpts3DTmp[k] = keypoints3D[iter->second];
384  }
385  if(descriptors.rows)
386  {
387  if(descriptors.type() == CV_32FC1)
388  {
389  memcpy(descriptorsTmp.ptr<float>(k), descriptors.ptr<float>(iter->second), descriptors.cols*sizeof(float));
390  }
391  else
392  {
393  memcpy(descriptorsTmp.ptr<char>(k), descriptors.ptr<char>(iter->second), descriptors.cols*sizeof(char));
394  }
395  }
396  }
397  }
398  ULOGGER_DEBUG("%d keypoints removed, (kept %d), minimum response=%f", removed, (int)kptsTmp.size(), !ssc&&kptsTmp.size()?kptsTmp.back().response:0.0f);
399  ULOGGER_DEBUG("removing words time = %f s", timer.ticks());
400  keypoints = kptsTmp;
401  keypoints3D = kpts3DTmp;
402  if(descriptors.rows)
403  {
404  descriptors = descriptorsTmp;
405  }
406  }
407 }
408 
409 void Feature2D::limitKeypoints(const std::vector<cv::KeyPoint> & keypoints, std::vector<bool> & inliers, int maxKeypoints, const cv::Size & imageSize, bool ssc)
410 {
411  if(maxKeypoints > 0 && (int)keypoints.size() > maxKeypoints)
412  {
413  UTimer timer;
414  float minimumHessian = 0.0f;
415  int removed;
416  inliers.resize(keypoints.size(), false);
417  if(ssc)
418  {
419  ULOGGER_DEBUG("too much words (%d), removing words with SSC", keypoints.size());
420 
421  // Sorting keypoints by deacreasing order of strength
422  std::vector<float> responseVector;
423  for (unsigned int i = 0; i < keypoints.size(); i++)
424  {
425  responseVector.push_back(keypoints[i].response);
426  }
427  std::vector<int> indx(responseVector.size());
428  std::iota(std::begin(indx), std::end(indx), 0);
429 
430 #if CV_MAJOR_VERSION >= 4
431  cv::sortIdx(responseVector, indx, cv::SORT_DESCENDING);
432 #else
433  cv::sortIdx(responseVector, indx, CV_SORT_DESCENDING);
434 #endif
435 
436  static constexpr float tolerance = 0.1;
437  auto ResultVec = util2d::SSC(keypoints, maxKeypoints, tolerance, imageSize.width, imageSize.height, indx);
438  removed = keypoints.size()-ResultVec.size();
439  for(unsigned int k=0; k<ResultVec.size(); ++k)
440  {
441  inliers[ResultVec[k]] = true;
442  }
443  }
444  else
445  {
446  ULOGGER_DEBUG("too much words (%d), removing words with the hessian threshold", keypoints.size());
447  // Remove words under the new hessian threshold
448 
449  // Sort words by hessian
450  std::multimap<float, int> hessianMap; // <hessian,id>
451  for(unsigned int i = 0; i<keypoints.size(); ++i)
452  {
453  //Keep track of the data, to be easier to manage the data in the next step
454  hessianMap.insert(std::pair<float, int>(fabs(keypoints[i].response), i));
455  }
456 
457  // Keep keypoints with highest response
458  removed = (int)hessianMap.size()-maxKeypoints;
459  std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
460  for(int k=0; k<maxKeypoints && iter!=hessianMap.rend(); ++k, ++iter)
461  {
462  inliers[iter->second] = true;
463  minimumHessian = iter->first;
464  }
465  }
466  ULOGGER_DEBUG("%d keypoints removed, (kept %d), minimum response=%f", removed, maxKeypoints, minimumHessian);
467  ULOGGER_DEBUG("filter keypoints time = %f s", timer.ticks());
468  }
469  else
470  {
471  ULOGGER_DEBUG("keeping all %d keypoints", (int)keypoints.size());
472  inliers.resize(keypoints.size(), true);
473  }
474 }
475 
476 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)
477 {
478  if(maxKeypoints <= 0 || (int)keypoints.size() <= maxKeypoints)
479  {
480  inliers.resize(keypoints.size(), true);
481  return;
482  }
483  UASSERT(gridCols>=1 && gridRows >=1);
484  UASSERT(imageSize.height>gridRows && imageSize.width>gridCols);
485  int rowSize = imageSize.height / gridRows;
486  int colSize = imageSize.width / gridCols;
487  int maxKeypointsPerCell = maxKeypoints / (gridRows * gridCols);
488  std::vector<std::vector<cv::KeyPoint> > keypointsPerCell(gridRows * gridCols);
489  std::vector<std::vector<int> > indexesPerCell(gridRows * gridCols);
490  for(size_t i=0; i<keypoints.size(); ++i)
491  {
492  int cellRow = int(keypoints[i].pt.y)/rowSize;
493  int cellCol = int(keypoints[i].pt.x)/colSize;
494  UASSERT(cellRow >=0 && cellRow < gridRows);
495  UASSERT(cellCol >=0 && cellCol < gridCols);
496 
497  keypointsPerCell[cellRow*gridCols + cellCol].push_back(keypoints[i]);
498  indexesPerCell[cellRow*gridCols + cellCol].push_back(i);
499  }
500  inliers.resize(keypoints.size(), false);
501  for(size_t i=0; i<keypointsPerCell.size(); ++i)
502  {
503  std::vector<bool> inliersCell;
504  limitKeypoints(keypointsPerCell[i], inliersCell, maxKeypointsPerCell, cv::Size(colSize, rowSize), ssc);
505  for(size_t j=0; j<inliersCell.size(); ++j)
506  {
507  if(inliersCell[j])
508  {
509  inliers.at(indexesPerCell[i][j]) = true;
510  }
511  }
512  }
513 }
514 
515 cv::Rect Feature2D::computeRoi(const cv::Mat & image, const std::string & roiRatios)
516 {
517  return util2d::computeRoi(image, roiRatios);
518 }
519 
520 cv::Rect Feature2D::computeRoi(const cv::Mat & image, const std::vector<float> & roiRatios)
521 {
522  return util2d::computeRoi(image, roiRatios);
523 }
524 
526 // Feature2D
528 Feature2D::Feature2D(const ParametersMap & parameters) :
529  maxFeatures_(Parameters::defaultKpMaxFeatures()),
530  SSC_(Parameters::defaultKpSSC()),
531  _maxDepth(Parameters::defaultKpMaxDepth()),
532  _minDepth(Parameters::defaultKpMinDepth()),
533  _roiRatios(std::vector<float>(4, 0.0f)),
534  _subPixWinSize(Parameters::defaultKpSubPixWinSize()),
535  _subPixIterations(Parameters::defaultKpSubPixIterations()),
536  _subPixEps(Parameters::defaultKpSubPixEps()),
537  gridRows_(Parameters::defaultKpGridRows()),
538  gridCols_(Parameters::defaultKpGridCols())
539 {
540  _stereo = new Stereo(parameters);
541  this->parseParameters(parameters);
542 }
544 {
545  delete _stereo;
546 }
548 {
549  uInsert(parameters_, parameters);
550 
551  Parameters::parse(parameters, Parameters::kKpMaxFeatures(), maxFeatures_);
552  Parameters::parse(parameters, Parameters::kKpSSC(), SSC_);
553  Parameters::parse(parameters, Parameters::kKpMaxDepth(), _maxDepth);
554  Parameters::parse(parameters, Parameters::kKpMinDepth(), _minDepth);
555  Parameters::parse(parameters, Parameters::kKpSubPixWinSize(), _subPixWinSize);
556  Parameters::parse(parameters, Parameters::kKpSubPixIterations(), _subPixIterations);
557  Parameters::parse(parameters, Parameters::kKpSubPixEps(), _subPixEps);
558  Parameters::parse(parameters, Parameters::kKpGridRows(), gridRows_);
559  Parameters::parse(parameters, Parameters::kKpGridCols(), gridCols_);
560 
561  UASSERT(gridRows_ >= 1 && gridCols_>=1);
562 
563  // convert ROI from string to vector
564  ParametersMap::const_iterator iter;
565  if((iter=parameters.find(Parameters::kKpRoiRatios())) != parameters.end())
566  {
567  std::list<std::string> strValues = uSplit(iter->second, ' ');
568  if(strValues.size() != 4)
569  {
570  ULOGGER_ERROR("The number of values must be 4 (roi=\"%s\")", iter->second.c_str());
571  }
572  else
573  {
574  std::vector<float> tmpValues(4);
575  unsigned int i=0;
576  for(std::list<std::string>::iterator jter = strValues.begin(); jter!=strValues.end(); ++jter)
577  {
578  tmpValues[i] = uStr2Float(*jter);
579  ++i;
580  }
581 
582  if(tmpValues[0] >= 0 && tmpValues[0] < 1 && tmpValues[0] < 1.0f-tmpValues[1] &&
583  tmpValues[1] >= 0 && tmpValues[1] < 1 && tmpValues[1] < 1.0f-tmpValues[0] &&
584  tmpValues[2] >= 0 && tmpValues[2] < 1 && tmpValues[2] < 1.0f-tmpValues[3] &&
585  tmpValues[3] >= 0 && tmpValues[3] < 1 && tmpValues[3] < 1.0f-tmpValues[2])
586  {
587  _roiRatios = tmpValues;
588  }
589  else
590  {
591  ULOGGER_ERROR("The roi ratios are not valid (roi=\"%s\")", iter->second.c_str());
592  }
593  }
594  }
595 
596  //stereo
597  UASSERT(_stereo != 0);
598  if((iter=parameters.find(Parameters::kStereoOpticalFlow())) != parameters.end())
599  {
600  delete _stereo;
602  }
603  else
604  {
605  _stereo->parseParameters(parameters);
606  }
607 }
609 {
610  int type = Parameters::defaultKpDetectorStrategy();
611  Parameters::parse(parameters, Parameters::kKpDetectorStrategy(), type);
612  return create((Feature2D::Type)type, parameters);
613 }
615 {
616 
617 // NONFREE checks
618 #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)))
619 
620  #ifndef RTABMAP_NONFREE
622  {
623  #if CV_MAJOR_VERSION < 3
624  UWARN("SURF and SIFT features cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
625  #else
626  UWARN("SURF and SIFT features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
627  #endif
629  }
630  #endif
631 
632 #else // >= 4.4.0 >= 3.4.11
633 
634  #ifndef RTABMAP_NONFREE
636  {
637  UWARN("SURF features cannot be used because OpenCV was not built with nonfree module. SIFT is used instead.");
639  }
641  {
642  UWARN("SURF detector cannot be used because OpenCV was not built with nonfree module. GFTT/ORB is used instead.");
644  }
645  #endif
646 
647 #endif // >= 4.4.0 >= 3.4.11
648 
649 #if !defined(HAVE_OPENCV_XFEATURES2D) && CV_MAJOR_VERSION >= 3
657  {
658  UWARN("BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.");
660  }
661 #elif CV_MAJOR_VERSION < 3
663  {
664  #ifdef RTABMAP_NONFREE
665  UWARN("KAZE detector/descriptor can be used only with OpenCV3. SURF is used instead.");
667  #else
668  UWARN("KAZE detector/descriptor can be used only with OpenCV3. GFTT/ORB is used instead.");
670  #endif
671  }
673  {
674  UWARN("DAISY detector/descriptor can be used only with OpenCV3. GFTT/BRIEF is used instead.");
676  }
677 #endif
678 
679 
680 #ifndef RTABMAP_ORB_OCTREE
682  {
683  UWARN("ORB OcTree feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
685  }
686 #endif
687 
688 #ifndef RTABMAP_TORCH
690  {
691  UWARN("SupertPoint Torch feature cannot be used as RTAB-Map is not built with the option enabled. GFTT/ORB is used instead.");
693  }
694 #endif
695 
696  Feature2D * feature2D = 0;
697  switch(type)
698  {
700  feature2D = new SURF(parameters);
701  break;
703  feature2D = new SIFT(parameters);
704  break;
706  feature2D = new ORB(parameters);
707  break;
709  feature2D = new FAST_BRIEF(parameters);
710  break;
712  feature2D = new FAST_FREAK(parameters);
713  break;
715  feature2D = new GFTT_FREAK(parameters);
716  break;
718  feature2D = new GFTT_BRIEF(parameters);
719  break;
721  feature2D = new GFTT_ORB(parameters);
722  break;
724  feature2D = new BRISK(parameters);
725  break;
727  feature2D = new KAZE(parameters);
728  break;
730  feature2D = new ORBOctree(parameters);
731  break;
732 #ifdef RTABMAP_TORCH
734  feature2D = new SuperPointTorch(parameters);
735  break;
736 #endif
738  feature2D = new SURF_FREAK(parameters);
739  break;
741  feature2D = new GFTT_DAISY(parameters);
742  break;
744  feature2D = new SURF_DAISY(parameters);
745  break;
746 #ifdef RTABMAP_PYTHON
748  feature2D = new PyDetector(parameters);
749  break;
750 #endif
751 #ifdef RTABMAP_NONFREE
752  default:
753  feature2D = new SURF(parameters);
755  break;
756 #else
757  default:
758  feature2D = new ORB(parameters);
760  break;
761 #endif
762 
763  }
764  return feature2D;
765 }
766 
767 std::vector<cv::KeyPoint> Feature2D::generateKeypoints(const cv::Mat & image, const cv::Mat & maskIn)
768 {
769  UASSERT(!image.empty());
770  UASSERT(image.type() == CV_8UC1);
771 
772  cv::Mat mask;
773  if(!maskIn.empty())
774  {
775  if(maskIn.type()==CV_16UC1 || maskIn.type() == CV_32FC1)
776  {
777  mask = cv::Mat::zeros(maskIn.rows, maskIn.cols, CV_8UC1);
778  for(int i=0; i<(int)mask.total(); ++i)
779  {
780  float value = 0.0f;
781  if(maskIn.type()==CV_16UC1)
782  {
783  if(((unsigned short*)maskIn.data)[i] > 0 &&
784  ((unsigned short*)maskIn.data)[i] < std::numeric_limits<unsigned short>::max())
785  {
786  value = float(((unsigned short*)maskIn.data)[i])*0.001f;
787  }
788  }
789  else
790  {
791  value = ((float*)maskIn.data)[i];
792  }
793 
794  if(value>_minDepth &&
795  (_maxDepth == 0.0f || value <= _maxDepth) &&
796  uIsFinite(value))
797  {
798  ((unsigned char*)mask.data)[i] = 255; // ORB uses 255 to handle pyramids
799  }
800  }
801  }
802  else if(maskIn.type()==CV_8UC1)
803  {
804  // assume a standard mask
805  mask = maskIn;
806  }
807  else
808  {
809  UERROR("Wrong mask type (%d)! Should be 8UC1, 16UC1 or 32FC1.", maskIn.type());
810  }
811  }
812 
813  UASSERT(mask.empty() || (mask.cols == image.cols && mask.rows == image.rows));
814 
815  std::vector<cv::KeyPoint> keypoints;
816  UTimer timer;
817  cv::Rect globalRoi = Feature2D::computeRoi(image, _roiRatios);
818  if(!(globalRoi.width && globalRoi.height))
819  {
820  globalRoi = cv::Rect(0,0,image.cols, image.rows);
821  }
822 
823  // Get keypoints
824  int rowSize = globalRoi.height / gridRows_;
825  int colSize = globalRoi.width / gridCols_;
826  int maxFeatures = maxFeatures_ / (gridRows_ * gridCols_);
827  for (int i = 0; i<gridRows_; ++i)
828  {
829  for (int j = 0; j<gridCols_; ++j)
830  {
831  cv::Rect roi(globalRoi.x + j*colSize, globalRoi.y + i*rowSize, colSize, rowSize);
832  std::vector<cv::KeyPoint> subKeypoints;
833  subKeypoints = this->generateKeypointsImpl(image, roi, mask);
834  if (this->getType() != Feature2D::Type::kFeaturePyDetector)
835  {
836  limitKeypoints(subKeypoints, maxFeatures, roi.size(), this->getSSC());
837  }
838  if(roi.x || roi.y)
839  {
840  // Adjust keypoint position to raw image
841  for(std::vector<cv::KeyPoint>::iterator iter=subKeypoints.begin(); iter!=subKeypoints.end(); ++iter)
842  {
843  iter->pt.x += roi.x;
844  iter->pt.y += roi.y;
845  }
846  }
847  keypoints.insert( keypoints.end(), subKeypoints.begin(), subKeypoints.end() );
848  }
849  }
850  UDEBUG("Keypoints extraction time = %f s, keypoints extracted = %d (grid=%dx%d, mask empty=%d)",
851  timer.ticks(), keypoints.size(), gridCols_, gridRows_, mask.empty()?1:0);
852 
853  if(keypoints.size() && _subPixWinSize > 0 && _subPixIterations > 0)
854  {
855  std::vector<cv::Point2f> corners;
856  cv::KeyPoint::convert(keypoints, corners);
857  cv::cornerSubPix( image, corners,
858  cv::Size( _subPixWinSize, _subPixWinSize ),
859  cv::Size( -1, -1 ),
860  cv::TermCriteria( CV_TERMCRIT_ITER | CV_TERMCRIT_EPS, _subPixIterations, _subPixEps ) );
861 
862  for(unsigned int i=0;i<corners.size(); ++i)
863  {
864  keypoints[i].pt = corners[i];
865  }
866  UDEBUG("subpixel time = %f s", timer.ticks());
867  }
868 
869  return keypoints;
870 }
871 
873  const cv::Mat & image,
874  std::vector<cv::KeyPoint> & keypoints) const
875 {
876  cv::Mat descriptors;
877  if(keypoints.size())
878  {
879  UASSERT(!image.empty());
880  UASSERT(image.type() == CV_8UC1);
881  descriptors = generateDescriptorsImpl(image, keypoints);
882  UASSERT_MSG(descriptors.rows == (int)keypoints.size(), uFormat("descriptors=%d, keypoints=%d", descriptors.rows, (int)keypoints.size()).c_str());
883  UDEBUG("Descriptors extracted = %d, remaining kpts=%d", descriptors.rows, (int)keypoints.size());
884  }
885  return descriptors;
886 }
887 
888 std::vector<cv::Point3f> Feature2D::generateKeypoints3D(
889  const SensorData & data,
890  const std::vector<cv::KeyPoint> & keypoints) const
891 {
892  std::vector<cv::Point3f> keypoints3D;
893  if(keypoints.size())
894  {
895  if(!data.rightRaw().empty() && !data.imageRaw().empty() &&
896  !data.stereoCameraModels().empty() &&
897  data.stereoCameraModels()[0].isValidForProjection())
898  {
899  //stereo
900  cv::Mat imageLeft = data.imageRaw();
901  cv::Mat imageRight = data.rightRaw();
902 #ifdef HAVE_OPENCV_CUDEV
903  cv::cuda::GpuMat d_imageLeft;
904  cv::cuda::GpuMat d_imageRight;
905  if(_stereo->isGpuEnabled())
906  {
907  d_imageLeft = data.imageRawGpu();
908  if(d_imageLeft.empty()) {
909  d_imageLeft = cv::cuda::GpuMat(imageLeft);
910  }
911  // convert to grayscale
912  if(d_imageLeft.channels() > 1) {
913  cv::cuda::GpuMat tmp;
914  cv::cuda::cvtColor(d_imageLeft, tmp, cv::COLOR_BGR2GRAY);
915  d_imageLeft = tmp;
916  }
917  d_imageRight = data.depthOrRightRawGpu();
918  if(d_imageRight.empty()) {
919  d_imageRight = cv::cuda::GpuMat(imageRight);
920  }
921  }
922  else
923 #endif
924  {
925  // convert to grayscale (right image should be already grayscale)
926  if(imageLeft.channels() > 1)
927  {
928  cv::cvtColor(data.imageRaw(), imageLeft, cv::COLOR_BGR2GRAY);
929  }
930  }
931 
932  std::vector<cv::Point2f> leftCorners;
933  cv::KeyPoint::convert(keypoints, leftCorners);
934 
935  std::vector<cv::Point2f> rightCorners;
936 
937  if(data.stereoCameraModels().size() == 1)
938  {
939  std::vector<unsigned char> status;
940 #ifdef HAVE_OPENCV_CUDEV
941  if(_stereo->isGpuEnabled())
942  {
943  rightCorners = _stereo->computeCorrespondences(
944  d_imageLeft,
945  d_imageRight,
946  leftCorners,
947  status);
948  }
949  else
950 #endif
951  {
952  rightCorners = _stereo->computeCorrespondences(
953  imageLeft,
954  imageRight,
955  leftCorners,
956  status);
957  }
958 
960  {
961  int rejected = 0;
962  for(size_t i=0; i<status.size(); ++i)
963  {
964  if(status[i]==0)
965  {
966  ++rejected;
967  }
968  }
969  if(rejected > (int)status.size()/2)
970  {
971  UWARN("A large number (%d/%d) of stereo correspondences are rejected! "
972  "Optical flow may have failed because images are not calibrated, "
973  "the background is too far (no disparity between the images), "
974  "maximum disparity may be too small (%f) or that exposure between "
975  "left and right images is too different.",
976  rejected,
977  (int)status.size(),
978  _stereo->maxDisparity());
979  }
980  }
981 
982  keypoints3D = util3d::generateKeypoints3DStereo(
983  leftCorners,
984  rightCorners,
985  data.stereoCameraModels()[0],
986  status,
987  _minDepth,
988  _maxDepth);
989  }
990  else
991  {
992  int subImageWith = imageLeft.cols / data.stereoCameraModels().size();
993  UASSERT(imageLeft.cols % subImageWith == 0);
994  std::vector<std::vector<cv::Point2f> > subLeftCorners(data.stereoCameraModels().size());
995  std::vector<std::vector<int> > subIndex(data.stereoCameraModels().size());
996  // Assign keypoints per camera
997  for(size_t i=0; i<leftCorners.size(); ++i)
998  {
999  int cameraIndex = int(leftCorners[i].x / subImageWith);
1000  leftCorners[i].x -= cameraIndex*subImageWith;
1001  subLeftCorners[cameraIndex].push_back(leftCorners[i]);
1002  subIndex[cameraIndex].push_back(i);
1003  }
1004 
1005  keypoints3D.resize(keypoints.size());
1006  int total = 0;
1007  int rejected = 0;
1008  for(size_t i=0; i<data.stereoCameraModels().size(); ++i)
1009  {
1010  if(!subLeftCorners[i].empty())
1011  {
1012  std::vector<unsigned char> status;
1013 #ifdef HAVE_OPENCV_CUDEV
1014  if(_stereo->isGpuEnabled())
1015  {
1016  rightCorners = _stereo->computeCorrespondences(
1017  d_imageLeft.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1018  d_imageRight.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1019  subLeftCorners[i],
1020  status);
1021  }
1022  else
1023 #endif
1024  {
1025  rightCorners = _stereo->computeCorrespondences(
1026  imageLeft.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1027  imageRight.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1028  subLeftCorners[i],
1029  status);
1030  }
1031 
1032  std::vector<cv::Point3f> subKeypoints3D = util3d::generateKeypoints3DStereo(
1033  subLeftCorners[i],
1034  rightCorners,
1035  data.stereoCameraModels()[i],
1036  status,
1037  _minDepth,
1038  _maxDepth);
1039 
1041  {
1042  for(size_t i=0; i<status.size(); ++i)
1043  {
1044  if(status[i]==0)
1045  {
1046  ++rejected;
1047  }
1048  }
1049  total+=status.size();
1050  }
1051 
1052  UASSERT(subIndex[i].size() == subKeypoints3D.size());
1053  for(size_t j=0; j<subKeypoints3D.size(); ++j)
1054  {
1055  keypoints3D[subIndex[i][j]] = subKeypoints3D[j];
1056  }
1057  }
1058  }
1059 
1061  {
1062  if(rejected > total/2)
1063  {
1064  UWARN("A large number (%d/%d) of stereo correspondences are rejected! "
1065  "Optical flow may have failed because images are not calibrated, "
1066  "the background is too far (no disparity between the images), "
1067  "maximum disparity may be too small (%f) or that exposure between "
1068  "left and right images is too different.",
1069  rejected,
1070  total,
1071  _stereo->maxDisparity());
1072  }
1073  }
1074  }
1075  }
1076  else if(!data.depthRaw().empty() && data.cameraModels().size())
1077  {
1078  keypoints3D = util3d::generateKeypoints3DDepth(
1079  keypoints,
1080  data.depthOrRightRaw(),
1081  data.cameraModels(),
1082  _minDepth,
1083  _maxDepth);
1084  }
1085  }
1086 
1087  return keypoints3D;
1088 }
1089 
1091 //SURF
1093 SURF::SURF(const ParametersMap & parameters) :
1094  hessianThreshold_(Parameters::defaultSURFHessianThreshold()),
1095  nOctaves_(Parameters::defaultSURFOctaves()),
1096  nOctaveLayers_(Parameters::defaultSURFOctaveLayers()),
1097  extended_(Parameters::defaultSURFExtended()),
1098  upright_(Parameters::defaultSURFUpright()),
1099  gpuKeypointsRatio_(Parameters::defaultSURFGpuKeypointsRatio()),
1100  gpuVersion_(Parameters::defaultSURFGpuVersion())
1101 {
1102  parseParameters(parameters);
1103 }
1104 
1106 {
1107 }
1108 
1109 void SURF::parseParameters(const ParametersMap & parameters)
1110 {
1111  Feature2D::parseParameters(parameters);
1112 
1113  Parameters::parse(parameters, Parameters::kSURFExtended(), extended_);
1114  Parameters::parse(parameters, Parameters::kSURFHessianThreshold(), hessianThreshold_);
1115  Parameters::parse(parameters, Parameters::kSURFOctaveLayers(), nOctaveLayers_);
1116  Parameters::parse(parameters, Parameters::kSURFOctaves(), nOctaves_);
1117  Parameters::parse(parameters, Parameters::kSURFUpright(), upright_);
1118  Parameters::parse(parameters, Parameters::kSURFGpuKeypointsRatio(), gpuKeypointsRatio_);
1119  Parameters::parse(parameters, Parameters::kSURFGpuVersion(), gpuVersion_);
1120 
1121 #ifdef RTABMAP_NONFREE
1122 #if CV_MAJOR_VERSION < 3
1123  if(gpuVersion_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1124  {
1125  UWARN("GPU version of SURF not available! Using CPU version instead...");
1126  gpuVersion_ = false;
1127  }
1128 #else
1129  if(gpuVersion_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1130  {
1131  UWARN("GPU version of SURF not available! Using CPU version instead...");
1132  gpuVersion_ = false;
1133  }
1134 #endif
1135  if(gpuVersion_)
1136  {
1138  }
1139  else
1140  {
1141 #if CV_MAJOR_VERSION < 3
1143 #else
1145 #endif
1146  }
1147 #else
1148  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1149 #endif
1150 }
1151 
1152 std::vector<cv::KeyPoint> SURF::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1153 {
1154  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1155  std::vector<cv::KeyPoint> keypoints;
1156 
1157 #ifdef RTABMAP_NONFREE
1158  cv::Mat imgRoi(image, roi);
1159  cv::Mat maskRoi;
1160  if(!mask.empty())
1161  {
1162  maskRoi = cv::Mat(mask, roi);
1163  }
1164  if(gpuVersion_)
1165  {
1166 #if CV_MAJOR_VERSION < 3
1167  cv::gpu::GpuMat imgGpu(imgRoi);
1168  cv::gpu::GpuMat maskGpu(maskRoi);
1169  (*_gpuSurf.obj)(imgGpu, maskGpu, keypoints);
1170 #else
1171  cv::cuda::GpuMat imgGpu(imgRoi);
1172  cv::cuda::GpuMat maskGpu(maskRoi);
1173  (*_gpuSurf.get())(imgGpu, maskGpu, keypoints);
1174 #endif
1175  }
1176  else
1177  {
1178  _surf->detect(imgRoi, keypoints, maskRoi);
1179  }
1180 #else
1181  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1182 #endif
1183  return keypoints;
1184 }
1185 
1186 cv::Mat SURF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1187 {
1188  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1189  cv::Mat descriptors;
1190 #ifdef RTABMAP_NONFREE
1191  if(gpuVersion_)
1192  {
1193 #if CV_MAJOR_VERSION < 3
1194  cv::gpu::GpuMat imgGpu(image);
1195  cv::gpu::GpuMat descriptorsGPU;
1196  (*_gpuSurf.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU, true);
1197 #else
1198  cv::cuda::GpuMat imgGpu(image);
1199  cv::cuda::GpuMat descriptorsGPU;
1200  (*_gpuSurf.get())(imgGpu, cv::cuda::GpuMat(), keypoints, descriptorsGPU, true);
1201 #endif
1202 
1203  // Download descriptors
1204  if (descriptorsGPU.empty())
1205  descriptors = cv::Mat();
1206  else
1207  {
1208  UASSERT(descriptorsGPU.type() == CV_32F);
1209  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1210  descriptorsGPU.download(descriptors);
1211  }
1212  }
1213  else
1214  {
1215  _surf->compute(image, keypoints, descriptors);
1216  }
1217 #else
1218  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1219 #endif
1220 
1221  return descriptors;
1222 }
1223 
1225 //SIFT
1227 SIFT::SIFT(const ParametersMap & parameters) :
1228  nOctaveLayers_(Parameters::defaultSIFTNOctaveLayers()),
1229  contrastThreshold_(Parameters::defaultSIFTContrastThreshold()),
1230  edgeThreshold_(Parameters::defaultSIFTEdgeThreshold()),
1231  sigma_(Parameters::defaultSIFTSigma()),
1232  preciseUpscale_(Parameters::defaultSIFTPreciseUpscale()),
1233  rootSIFT_(Parameters::defaultSIFTRootSIFT()),
1234  gpu_(Parameters::defaultSIFTGpu()),
1235  guaussianThreshold_(Parameters::defaultSIFTGaussianThreshold()),
1236  upscale_(Parameters::defaultSIFTUpscale()),
1237  cudaSiftData_(0),
1238  cudaSiftMemory_(0),
1239  cudaSiftUpscaling_(upscale_)
1240 {
1241  parseParameters(parameters);
1242 }
1243 
1245 {
1246 #ifdef RTABMAP_CUDASIFT
1247  if(cudaSiftData_) {
1248  FreeSiftData(*cudaSiftData_);
1249  delete cudaSiftData_;
1250  }
1251  if(cudaSiftMemory_) {
1252  FreeSiftTempMemory(cudaSiftMemory_);
1253  }
1254 #endif
1255 }
1256 
1257 void SIFT::parseParameters(const ParametersMap & parameters)
1258 {
1259  Feature2D::parseParameters(parameters);
1260 
1261  Parameters::parse(parameters, Parameters::kSIFTContrastThreshold(), contrastThreshold_);
1262  Parameters::parse(parameters, Parameters::kSIFTEdgeThreshold(), edgeThreshold_);
1263  Parameters::parse(parameters, Parameters::kSIFTNOctaveLayers(), nOctaveLayers_);
1264  Parameters::parse(parameters, Parameters::kSIFTSigma(), sigma_);
1265  Parameters::parse(parameters, Parameters::kSIFTPreciseUpscale(), preciseUpscale_);
1266  Parameters::parse(parameters, Parameters::kSIFTRootSIFT(), rootSIFT_);
1267  Parameters::parse(parameters, Parameters::kSIFTGpu(), gpu_);
1268  Parameters::parse(parameters, Parameters::kSIFTGaussianThreshold(), guaussianThreshold_);
1269  Parameters::parse(parameters, Parameters::kSIFTUpscale(), upscale_);
1270 
1271  if(gpu_)
1272  {
1273 #ifdef RTABMAP_CUDASIFT
1274  // Check if there is a cuda device
1275  if(InitCuda(0, ULogger::level() == ULogger::kDebug)) {
1276  UDEBUG("Init SiftData");
1277  if(cudaSiftData_ == 0) {
1278  cudaSiftData_ = new SiftData();
1279  InitSiftData(*cudaSiftData_, 8192, true, true);
1280  }
1281  }
1282  else{
1283  UWARN("No cuda device(s) detected, CudaSift is not available! Using SIFT CPU version instead.");
1284  gpu_ = false;
1285  }
1286 #else
1287  UWARN("RTAB-Map is not built with CudaSift so %s cannot be used!", Parameters::kSIFTGpu().c_str());
1288  gpu_ = false;
1289 #endif
1290  }
1291 
1292  if(!gpu_)
1293  {
1294  #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)))
1295 #ifdef RTABMAP_NONFREE
1296 #if CV_MAJOR_VERSION < 3
1297  sift_ = cv::Ptr<CV_SIFT>(new CV_SIFT(this->getMaxFeatures(), nOctaveLayers_, contrastThreshold_, edgeThreshold_, sigma_));
1298 #else
1300 #endif
1301 #else
1302  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1303 #endif
1304 #elif CV_MAJOR_VERSION>4 || (CV_MAJOR_VERSION==4 && CV_MINOR_VERSION>=8)// >=4.8
1306 #else // >=4.4, >=3.4.11
1308 #endif
1309  }
1310 
1311 }
1312 
1313 std::vector<cv::KeyPoint> SIFT::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1314 {
1315  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1316  std::vector<cv::KeyPoint> keypoints;
1317  cv::Mat imgRoi(image, roi);
1318  cv::Mat maskRoi;
1319  if(!mask.empty())
1320  {
1321  maskRoi = cv::Mat(mask, roi);
1322  }
1323 #ifdef RTABMAP_CUDASIFT
1324  if(gpu_)
1325  {
1326  /* Read image using OpenCV and convert to floating point. */
1327  int w = imgRoi.cols;
1328  int h = imgRoi.rows;
1329  cv::Mat img_h;
1330  imgRoi.convertTo(img_h, CV_32FC1);
1331  CudaImage img_d;
1332  img_d.Allocate(w, h, iAlignUp(w, 128), false, NULL, (float*)img_h.data);
1333  img_d.Download();
1334 
1335  // Compute number of octaves like OpenCV based on resolution
1336  // ref: https://github.com/opencv/opencv/blob/4d665419992dda6e40364f741ae4765176b64bb0/modules/features2d/src/sift.dispatch.cpp#L538
1337  // *** stack smashing detected *** if "-2" term is higher
1338  int numOctaves = cvRound(std::log( (double)std::min(w*(upscale_?2:1), h*(upscale_?2:1)) ) / std::log(2.) - (upscale_?3:2));
1339  if(numOctaves < 1) {
1340  numOctaves = 1;
1341  }
1342  else if (numOctaves>7)
1343  {
1344  numOctaves = 7; // hard-coded limit in CudaSift
1345  }
1346  float initBlur = sigma_; /* Amount of initial Gaussian blurring in standard deviations */
1347  float thresh = guaussianThreshold_; /* Threshold on difference of Gaussians for feature pruning */
1348  float edgeLimit = edgeThreshold_;
1349  float minScale = 0.0f; /* Minimum acceptable scale to remove fine-scale features */
1350  UDEBUG("numOctaves=%d initBlur=%f thresh=%f edgeLimit=%f minScale=%f upScale=%s w=%d h=%d", numOctaves, initBlur, thresh, edgeLimit, minScale, upscale_?"true":"false", w, h);
1351 
1352  if(cudaSiftMemory_ && (cudaSiftMemorySize_ != cv::Size(w, h) || cudaSiftUpscaling_ != upscale_)) {
1353  // Resolution changed, reset buffer
1354  FreeSiftTempMemory(cudaSiftMemory_);
1355  cudaSiftMemory_ = 0;
1356  }
1357 
1358  if(cudaSiftMemory_ == 0) {
1359  cudaSiftMemory_ = AllocSiftTempMemory(w, h, numOctaves, upscale_);
1360  UASSERT(cudaSiftMemory_ != 0);
1361  cudaSiftMemorySize_ = cv::Size(w, h);
1363  }
1364 
1365  ExtractSift(*cudaSiftData_, img_d, numOctaves, initBlur, thresh, edgeLimit, minScale, upscale_, cudaSiftMemory_);
1366  UDEBUG("%d features extracted", cudaSiftData_->numPts);
1367 
1368  // Convert CudaSift into OpenCV format
1369  cudaSiftDescriptors_ = cv::Mat();
1370  if(cudaSiftData_->numPts)
1371  {
1372  int maxKeypoints = this->getMaxFeatures();
1373  if(maxKeypoints == 0 || maxKeypoints > cudaSiftData_->numPts)
1374  {
1375  maxKeypoints = cudaSiftData_->numPts;
1376  }
1377 
1378  // Re-using same implementation of limitKeypoints() directly here to avoid doubling memory copies
1379  // Sort words by hessian
1380  std::multimap<float, int> hessianMap; // <hessian,id>
1381  for(int i=0; i<cudaSiftData_->numPts; ++i)
1382  {
1383  // Ignore keypoints with invalid descriptors
1384  float *desc = cudaSiftData_->h_data[i].data;
1385  if(desc[0] != 0 && desc[0] == desc[63] && desc[0] == desc[127])
1386  {
1387  //UWARN("Invalid decsriptor? skipping: %f,%f,%f", cudaSiftData_->h_data[i].xpos, cudaSiftData_->h_data[i].ypos, cudaSiftData_->h_data[i].scale);
1388  //std::cout << cv::Mat(1, 128*4, CV_8UC1, desc) << std::endl;
1389  continue;
1390  }
1391  // Ignore keypoints not in the mask
1392  if(!maskRoi.empty() && maskRoi.at<unsigned char>(cudaSiftData_->h_data[i].ypos, cudaSiftData_->h_data[i].xpos) == 0)
1393  {
1394  continue;
1395  }
1396 
1397  //Keep track of the data, to be easier to manage the data in the next step
1398  hessianMap.insert(std::pair<float, int>(cudaSiftData_->h_data[i].sharpness, i));
1399  }
1400 
1401  if((int)hessianMap.size() < maxKeypoints)
1402  {
1403  maxKeypoints = hessianMap.size();
1404  }
1405 
1406  std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
1407  keypoints.resize(maxKeypoints);
1408  cudaSiftDescriptors_ = cv::Mat(maxKeypoints, 128, CV_32FC1);
1409  for(unsigned int k=0; k<keypoints.size() && iter!=hessianMap.rend(); ++k, ++iter)
1410  {
1411  int i = iter->second;
1412  float *desc = cudaSiftData_->h_data[i].data;
1413  cv::Mat(1, 128, CV_32FC1, desc).copyTo(cudaSiftDescriptors_.row(k));
1414  keypoints[k].pt.x = cudaSiftData_->h_data[i].xpos;
1415  keypoints[k].pt.y = cudaSiftData_->h_data[i].ypos;
1416  keypoints[k].size = 2.0f*cudaSiftData_->h_data[i].scale; // x2 because the scale is more like a radius than a diameter, see CudaSift's ExtractSiftDescriptors function to see how they convert scale to patch size
1417  keypoints[k].angle = cudaSiftData_->h_data[i].orientation;
1418  keypoints[k].response = cudaSiftData_->h_data[i].sharpness;
1419  keypoints[k].octave = log2(cudaSiftData_->h_data[i].subsampling)-(upscale_?1:0);
1420  }
1421  }
1422  }
1423  else
1424 #endif
1425  {
1426 #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)))
1427 #ifdef RTABMAP_NONFREE
1428  sift_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1429 #else
1430  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1431 #endif
1432 #else // >=4.4, >=3.4.11
1433  sift_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1434 #endif
1435  }
1436  return keypoints;
1437 }
1438 
1439 cv::Mat SIFT::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1440 {
1441 #ifdef RTABMAP_CUDASIFT
1442  if(gpu_)
1443  {
1444  if((int)keypoints.size() == cudaSiftDescriptors_.rows)
1445  {
1446  return cudaSiftDescriptors_.clone();
1447  }
1448  else
1449  {
1450  UERROR("CudaSift: keypoints size %ld is not equal to extracted descriptors size %d", keypoints.size(), cudaSiftDescriptors_.rows);
1451  return cv::Mat();
1452  }
1453  }
1454 #endif
1455 
1456  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1457  cv::Mat descriptors;
1458 #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)))
1459 #ifdef RTABMAP_NONFREE
1460  sift_->compute(image, keypoints, descriptors);
1461 #else
1462  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1463 #endif
1464 #else // >=4.4, >=3.4.11
1465  sift_->compute(image, keypoints, descriptors);
1466 #endif
1467  if( rootSIFT_ && !descriptors.empty())
1468  {
1469  UDEBUG("Performing RootSIFT...");
1470  // see http://www.pyimagesearch.com/2015/04/13/implementing-rootsift-in-python-and-opencv/
1471  // apply the Hellinger kernel by first L1-normalizing and taking the
1472  // square-root
1473  for(int i=0; i<descriptors.rows; ++i)
1474  {
1475  // By taking the L1 norm, followed by the square-root, we have
1476  // already L2 normalized the feature vector and further normalization
1477  // is not needed.
1478  descriptors.row(i) = descriptors.row(i) / cv::sum(descriptors.row(i))[0];
1479  cv::sqrt(descriptors.row(i), descriptors.row(i));
1480  }
1481  }
1482  return descriptors;
1483 }
1484 
1486 //ORB
1488 ORB::ORB(const ParametersMap & parameters) :
1489  scaleFactor_(Parameters::defaultORBScaleFactor()),
1490  nLevels_(Parameters::defaultORBNLevels()),
1491  edgeThreshold_(Parameters::defaultORBEdgeThreshold()),
1492  firstLevel_(Parameters::defaultORBFirstLevel()),
1493  WTA_K_(Parameters::defaultORBWTA_K()),
1494  scoreType_(Parameters::defaultORBScoreType()),
1495  patchSize_(Parameters::defaultORBPatchSize()),
1496  gpu_(Parameters::defaultORBGpu()),
1497  fastThreshold_(Parameters::defaultFASTThreshold()),
1498  nonmaxSuppresion_(Parameters::defaultFASTNonmaxSuppression())
1499 {
1500  parseParameters(parameters);
1501 }
1502 
1504 {
1505 }
1506 
1507 void ORB::parseParameters(const ParametersMap & parameters)
1508 {
1509  Feature2D::parseParameters(parameters);
1510 
1511  Parameters::parse(parameters, Parameters::kORBScaleFactor(), scaleFactor_);
1512  Parameters::parse(parameters, Parameters::kORBNLevels(), nLevels_);
1513  Parameters::parse(parameters, Parameters::kORBEdgeThreshold(), edgeThreshold_);
1514  Parameters::parse(parameters, Parameters::kORBFirstLevel(), firstLevel_);
1515  Parameters::parse(parameters, Parameters::kORBWTA_K(), WTA_K_);
1516  Parameters::parse(parameters, Parameters::kORBScoreType(), scoreType_);
1517  Parameters::parse(parameters, Parameters::kORBPatchSize(), patchSize_);
1518  Parameters::parse(parameters, Parameters::kORBGpu(), gpu_);
1519 
1520  Parameters::parse(parameters, Parameters::kFASTThreshold(), fastThreshold_);
1521  Parameters::parse(parameters, Parameters::kFASTNonmaxSuppression(), nonmaxSuppresion_);
1522 
1523 #if CV_MAJOR_VERSION < 3
1524 #ifdef HAVE_OPENCV_GPU
1525  if(gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1526  {
1527  UWARN("GPU version of ORB not available! Using CPU version instead...");
1528  gpu_ = false;
1529  }
1530 #else
1531  if(gpu_)
1532  {
1533  UWARN("GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1534  gpu_ = false;
1535  }
1536 #endif
1537 #else
1538 #ifndef HAVE_OPENCV_CUDAFEATURES2D
1539  if(gpu_)
1540  {
1541  UWARN("GPU version of ORB not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1542  gpu_ = false;
1543  }
1544 #endif
1545  if(gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1546  {
1547  UWARN("GPU version of ORB not available (no GPU found)! Using CPU version instead...");
1548  gpu_ = false;
1549  }
1550 #endif
1551  if(gpu_)
1552  {
1553 #if CV_MAJOR_VERSION < 3
1554 #ifdef HAVE_OPENCV_GPU
1556  _gpuOrb->setFastParams(fastThreshold_, nonmaxSuppresion_);
1557 #else
1558  UFATAL("not supposed to be here");
1559 #endif
1560 #else
1561 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1563 #endif
1564 #endif
1565  }
1566  else
1567  {
1568 #if CV_MAJOR_VERSION < 3
1569  _orb = cv::Ptr<CV_ORB>(new CV_ORB(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, scoreType_, patchSize_, parameters));
1570 #elif CV_MAJOR_VERSION > 3
1571  _orb = CV_ORB::create(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, (cv::ORB::ScoreType)scoreType_, patchSize_, fastThreshold_);
1572 #else
1573  _orb = CV_ORB::create(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, scoreType_, patchSize_, fastThreshold_);
1574 #endif
1575  }
1576 }
1577 
1578 std::vector<cv::KeyPoint> ORB::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1579 {
1580  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1581  std::vector<cv::KeyPoint> keypoints;
1582  cv::Mat imgRoi(image, roi);
1583  cv::Mat maskRoi;
1584  if(!mask.empty())
1585  {
1586  maskRoi = cv::Mat(mask, roi);
1587  }
1588 
1589  if(gpu_)
1590  {
1591 #if CV_MAJOR_VERSION < 3
1592 #ifdef HAVE_OPENCV_GPU
1593  cv::gpu::GpuMat imgGpu(imgRoi);
1594  cv::gpu::GpuMat maskGpu(maskRoi);
1595  (*_gpuOrb.obj)(imgGpu, maskGpu, keypoints);
1596 #else
1597  UERROR("Cannot use ORBGPU because OpenCV is not built with gpu module.");
1598 #endif
1599 #else
1600 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1601  cv::cuda::GpuMat d_image(imgRoi);
1602  cv::cuda::GpuMat d_mask(maskRoi);
1603  try {
1604  _gpuOrb->detectAndCompute(d_image, d_mask, keypoints, cv::cuda::GpuMat(), false);
1605  } catch (cv::Exception& e) {
1606  const char* err_msg = e.what();
1607  UWARN("OpenCV exception caught: %s", err_msg);
1608  }
1609 #endif
1610 #endif
1611  }
1612  else
1613  {
1614  _orb->detect(imgRoi, keypoints, maskRoi);
1615  }
1616 
1617  return keypoints;
1618 }
1619 
1620 cv::Mat ORB::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1621 {
1622  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1623  cv::Mat descriptors;
1624  if(image.empty())
1625  {
1626  ULOGGER_ERROR("Image is null ?!?");
1627  return descriptors;
1628  }
1629  if(gpu_)
1630  {
1631 #if CV_MAJOR_VERSION < 3
1632 #ifdef HAVE_OPENCV_GPU
1633  cv::gpu::GpuMat imgGpu(image);
1634  cv::gpu::GpuMat descriptorsGPU;
1635  (*_gpuOrb.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU);
1636  // Download descriptors
1637  if (descriptorsGPU.empty())
1638  descriptors = cv::Mat();
1639  else
1640  {
1641  UASSERT(descriptorsGPU.type() == CV_32F);
1642  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1643  descriptorsGPU.download(descriptors);
1644  }
1645 #else
1646  UERROR("GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1647 #endif
1648 #else
1649 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1650  cv::cuda::GpuMat d_image(image);
1651  cv::cuda::GpuMat d_descriptors;
1652  try {
1653  _gpuOrb->detectAndCompute(d_image, cv::cuda::GpuMat(), keypoints, d_descriptors, true);
1654  } catch (cv::Exception& e) {
1655  const char* err_msg = e.what();
1656  UWARN("OpenCV exception caught: %s", err_msg);
1657  }
1658  // Download descriptors
1659  if (d_descriptors.empty())
1660  descriptors = cv::Mat();
1661  else
1662  {
1663  UASSERT(d_descriptors.type() == CV_32F || d_descriptors.type() == CV_8U);
1664  d_descriptors.download(descriptors);
1665  }
1666 #endif
1667 #endif
1668  }
1669  else
1670  {
1671  _orb->compute(image, keypoints, descriptors);
1672  }
1673 
1674  return descriptors;
1675 }
1676 
1678 //FAST
1680 FAST::FAST(const ParametersMap & parameters) :
1681  threshold_(Parameters::defaultFASTThreshold()),
1682  nonmaxSuppression_(Parameters::defaultFASTNonmaxSuppression()),
1683  gpu_(Parameters::defaultFASTGpu()),
1684  gpuKeypointsRatio_(Parameters::defaultFASTGpuKeypointsRatio()),
1685  minThreshold_(Parameters::defaultFASTMinThreshold()),
1686  maxThreshold_(Parameters::defaultFASTMaxThreshold()),
1687  gridRows_(Parameters::defaultFASTGridRows()),
1688  gridCols_(Parameters::defaultFASTGridCols()),
1689  fastCV_(Parameters::defaultFASTCV()),
1690  fastCVinit_(false),
1691  fastCVMaxFeatures_(10000),
1692  fastCVLastImageHeight_(0)
1693 {
1694 #ifdef RTABMAP_FASTCV
1695  char sVersion[128] = { 0 };
1696  fcvGetVersion(sVersion, 128);
1697  UINFO("fastcv version = %s", sVersion);
1698  int ix;
1699  if ((ix = fcvSetOperationMode(FASTCV_OP_PERFORMANCE)))
1700  {
1701  UERROR("fcvSetOperationMode return=%d, OpenCV FAST will be used instead!", ix);
1702  fastCV_ = 0;
1703  }
1704  else
1705  {
1706  fcvMemInit();
1707 
1708  if (!(fastCVCorners_ = (uint32_t*)fcvMemAlloc(fastCVMaxFeatures_ * sizeof(uint32_t) * 2, 16)) ||
1709  !(fastCVCornerScores_ = (uint32_t*)fcvMemAlloc( fastCVMaxFeatures_ * sizeof(uint32_t), 16 )))
1710  {
1711  UERROR("could not alloc fastcv mem, using opencv fast instead!");
1712 
1713  if (fastCVCorners_)
1714  {
1715  fcvMemFree(fastCVCorners_);
1716  fastCVCorners_ = NULL;
1717  }
1718  if (fastCVCornerScores_)
1719  {
1720  fcvMemFree(fastCVCornerScores_);
1722  }
1723  }
1724  else
1725  {
1726  fastCVinit_ = true;
1727  }
1728  }
1729  #endif
1730  parseParameters(parameters);
1731 }
1732 
1734 {
1735 #ifdef RTABMAP_FASTCV
1736  if(fastCVinit_)
1737  {
1738  fcvMemDeInit();
1739 
1740  if (fastCVCorners_)
1741  fcvMemFree(fastCVCorners_);
1742  if (fastCVCornerScores_)
1743  fcvMemFree(fastCVCornerScores_);
1744  if (fastCVTempBuf_)
1745  fcvMemFree(fastCVTempBuf_);
1746  }
1747 #endif
1748 }
1749 
1750 void FAST::parseParameters(const ParametersMap & parameters)
1751 {
1752  Feature2D::parseParameters(parameters);
1753 
1754  Parameters::parse(parameters, Parameters::kFASTThreshold(), threshold_);
1755  Parameters::parse(parameters, Parameters::kFASTNonmaxSuppression(), nonmaxSuppression_);
1756  Parameters::parse(parameters, Parameters::kFASTGpu(), gpu_);
1757  Parameters::parse(parameters, Parameters::kFASTGpuKeypointsRatio(), gpuKeypointsRatio_);
1758 
1759  Parameters::parse(parameters, Parameters::kFASTMinThreshold(), minThreshold_);
1760  Parameters::parse(parameters, Parameters::kFASTMaxThreshold(), maxThreshold_);
1761  Parameters::parse(parameters, Parameters::kFASTGridRows(), gridRows_);
1762  Parameters::parse(parameters, Parameters::kFASTGridCols(), gridCols_);
1763 
1764  Parameters::parse(parameters, Parameters::kFASTCV(), fastCV_);
1765  UASSERT(fastCV_ == 0 || fastCV_ == 9 || fastCV_ == 10);
1766 
1769 
1770 #if CV_MAJOR_VERSION < 3
1771 #ifdef HAVE_OPENCV_GPU
1772  if(gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1773  {
1774  UWARN("GPU version of FAST not available! Using CPU version instead...");
1775  gpu_ = false;
1776  }
1777 #else
1778  if(gpu_)
1779  {
1780  UWARN("GPU version of FAST not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1781  gpu_ = false;
1782  }
1783 #endif
1784 #else
1785 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1786  if(gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1787  {
1788  UWARN("GPU version of FAST not available! Using CPU version instead...");
1789  gpu_ = false;
1790  }
1791 #else
1792  if(gpu_)
1793  {
1794  UWARN("GPU version of FAST not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1795  gpu_ = false;
1796  }
1797 #endif
1798 #endif
1799  if(gpu_)
1800  {
1801 #if CV_MAJOR_VERSION < 3
1802 #ifdef HAVE_OPENCV_GPU
1804 #else
1805  UFATAL("not supposed to be here!");
1806 #endif
1807 #else
1808 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1809  UFATAL("not implemented");
1810 #endif
1811 #endif
1812  }
1813  else
1814  {
1815 #if CV_MAJOR_VERSION < 3
1816  if(gridRows_ > 0 && gridCols_ > 0)
1817  {
1818  UDEBUG("grid max features = %d", this->getMaxFeatures());
1819  cv::Ptr<cv::FeatureDetector> fastAdjuster = cv::Ptr<cv::FastAdjuster>(new cv::FastAdjuster(threshold_, nonmaxSuppression_, minThreshold_, maxThreshold_));
1820  _fast = cv::Ptr<cv::FeatureDetector>(new cv::GridAdaptedFeatureDetector(fastAdjuster, this->getMaxFeatures(), gridRows_, gridCols_));
1821  }
1822  else
1823  {
1824  if(gridRows_ > 0)
1825  {
1826  UWARN("Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1827  Parameters::kFASTGridRows().c_str(), gridRows_, Parameters::kFASTGridCols().c_str());
1828  }
1829  else if(gridCols_ > 0)
1830  {
1831  UWARN("Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1832  Parameters::kFASTGridCols().c_str(), gridCols_, Parameters::kFASTGridRows().c_str());
1833  }
1834  _fast = cv::Ptr<cv::FeatureDetector>(new CV_FAST(threshold_, nonmaxSuppression_));
1835  }
1836 #else
1837  _fast = CV_FAST::create(threshold_, nonmaxSuppression_);
1838 #endif
1839  }
1840 }
1841 
1842 std::vector<cv::KeyPoint> FAST::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1843 {
1844  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1845  std::vector<cv::KeyPoint> keypoints;
1846 
1847 #ifdef RTABMAP_FASTCV
1848  if(fastCV_>0)
1849  {
1850  // Note: mask not supported, it should be the inverse of the current mask used (0=where to extract)
1851  uint32_t nCorners = 0;
1852 
1854  if (nonmaxSuppression_)
1855  {
1856  if(fastCVTempBuf_==NULL || (fastCVTempBuf_!= NULL && fastCVLastImageHeight_!= image.rows))
1857  {
1858  if (fastCVTempBuf_)
1859  {
1860  fcvMemFree(fastCVTempBuf_);
1861  fastCVTempBuf_ = NULL;
1862  }
1863  if(!(fastCVTempBuf_ = (uint32_t*)fcvMemAlloc( (3*fastCVMaxFeatures_+image.rows+1)*4, 16 )))
1864  {
1865  UERROR("could not alloc fastcv mem for temp buf (%s=true)", Parameters::kFASTNonmaxSuppression().c_str());
1867  return keypoints;
1868  }
1869  fastCVLastImageHeight_ = image.rows;
1870  }
1871  }
1872 
1873  // image.data should be 128 bits aligned
1874  UDEBUG("%dx%d (step=%d) thr=%d maxFeatures=%d", image.cols, image.rows, image.step1(), threshold_, fastCVMaxFeatures_);
1875  if(fastCV_ == 10)
1876  {
1877  fcvCornerFast10Scoreu8(image.data, image.cols, image.rows, 0, threshold_, 0, fastCVCorners_, fastCVCornerScores_, fastCVMaxFeatures_, &nCorners, nonmaxSuppression_?1:0, fastCVTempBuf_);
1878  }
1879  else
1880  {
1881  fcvCornerFast9Scoreu8_v2(image.data, image.cols, image.rows, image.step1(), threshold_, 0, fastCVCorners_, fastCVCornerScores_, fastCVMaxFeatures_, &nCorners, nonmaxSuppression_?1:0, fastCVTempBuf_);
1882  }
1883  UDEBUG("number of corners found = %d:", nCorners);
1884  keypoints.resize(nCorners);
1885  for (uint32_t i = 0; i < nCorners; i++)
1886  {
1887  keypoints[i].pt.x = fastCVCorners_[i * 2];
1888  keypoints[i].pt.y = fastCVCorners_[(i * 2) + 1];
1889  keypoints[i].size = 3;
1890  keypoints[i].response = fastCVCornerScores_[i];
1891  }
1892 
1893  if(this->getMaxFeatures() > 0)
1894  {
1895  this->limitKeypoints(keypoints, this->getMaxFeatures());
1896  }
1897  return keypoints;
1898  }
1899 #endif
1900 
1901  if(fastCV_>0)
1902  {
1903  UWARN( "RTAB-Map is not built with FastCV support. OpenCV's FAST is used instead. "
1904  "Please set %s to 0. This message will only appear once.",
1905  Parameters::kFASTCV().c_str());
1906  fastCV_ = 0;
1907  }
1908 
1909  cv::Mat imgRoi(image, roi);
1910  cv::Mat maskRoi;
1911  if(!mask.empty())
1912  {
1913  maskRoi = cv::Mat(mask, roi);
1914  }
1915  if(gpu_)
1916  {
1917 #if CV_MAJOR_VERSION < 3
1918 #ifdef HAVE_OPENCV_GPU
1919  cv::gpu::GpuMat imgGpu(imgRoi);
1920  cv::gpu::GpuMat maskGpu(maskRoi);
1921  (*_gpuFast.obj)(imgGpu, maskGpu, keypoints);
1922 #else
1923  UERROR("Cannot use FAST GPU because OpenCV is not built with gpu module.");
1924 #endif
1925 #else
1926 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1927  UFATAL("not implemented");
1928 #endif
1929 #endif
1930  }
1931  else
1932  {
1933  _fast->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1934  }
1935  return keypoints;
1936 }
1937 
1939 //FAST-BRIEF
1942  FAST(parameters),
1943  bytes_(Parameters::defaultBRIEFBytes())
1944 {
1945  parseParameters(parameters);
1946 }
1947 
1949 {
1950 }
1951 
1953 {
1954  FAST::parseParameters(parameters);
1955 
1956  Parameters::parse(parameters, Parameters::kBRIEFBytes(), bytes_);
1957 #if CV_MAJOR_VERSION < 3
1958  _brief = cv::Ptr<CV_BRIEF>(new CV_BRIEF(bytes_));
1959 #else
1960 #ifdef HAVE_OPENCV_XFEATURES2D
1961  _brief = CV_BRIEF::create(bytes_);
1962 #else
1963  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1964 #endif
1965 #endif
1966 }
1967 
1968 cv::Mat FAST_BRIEF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1969 {
1970  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1971  cv::Mat descriptors;
1972 #if CV_MAJOR_VERSION < 3
1973  _brief->compute(image, keypoints, descriptors);
1974 #else
1975 #ifdef HAVE_OPENCV_XFEATURES2D
1976  _brief->compute(image, keypoints, descriptors);
1977 #else
1978  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1979 #endif
1980 #endif
1981  return descriptors;
1982 }
1983 
1985 //FAST-FREAK
1988  FAST(parameters),
1989  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
1990  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
1991  patternScale_(Parameters::defaultFREAKPatternScale()),
1992  nOctaves_(Parameters::defaultFREAKNOctaves())
1993 {
1994  parseParameters(parameters);
1995 }
1996 
1998 {
1999 }
2000 
2002 {
2003  FAST::parseParameters(parameters);
2004 
2005  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2006  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2007  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2008  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2009 
2010 #if CV_MAJOR_VERSION < 3
2012 #else
2013 #ifdef HAVE_OPENCV_XFEATURES2D
2015 #else
2016  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2017 #endif
2018 #endif
2019 }
2020 
2021 cv::Mat FAST_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2022 {
2023  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2024  cv::Mat descriptors;
2025 #if CV_MAJOR_VERSION < 3
2026  _freak->compute(image, keypoints, descriptors);
2027 #else
2028 #ifdef HAVE_OPENCV_XFEATURES2D
2029  _freak->compute(image, keypoints, descriptors);
2030 #else
2031  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2032 #endif
2033 #endif
2034  return descriptors;
2035 }
2036 
2038 //GFTT
2040 GFTT::GFTT(const ParametersMap & parameters) :
2041  _qualityLevel(Parameters::defaultGFTTQualityLevel()),
2042  _minDistance(Parameters::defaultGFTTMinDistance()),
2043  _blockSize(Parameters::defaultGFTTBlockSize()),
2044  _useHarrisDetector(Parameters::defaultGFTTUseHarrisDetector()),
2045  _k(Parameters::defaultGFTTK()),
2046  _gpu(Parameters::defaultGFTTGpu())
2047 {
2048  parseParameters(parameters);
2049 }
2050 
2052 {
2053 }
2054 
2055 void GFTT::parseParameters(const ParametersMap & parameters)
2056 {
2057  Feature2D::parseParameters(parameters);
2058 
2059  Parameters::parse(parameters, Parameters::kGFTTQualityLevel(), _qualityLevel);
2060  Parameters::parse(parameters, Parameters::kGFTTMinDistance(), _minDistance);
2061  Parameters::parse(parameters, Parameters::kGFTTBlockSize(), _blockSize);
2062  Parameters::parse(parameters, Parameters::kGFTTUseHarrisDetector(), _useHarrisDetector);
2063  Parameters::parse(parameters, Parameters::kGFTTK(), _k);
2064  Parameters::parse(parameters, Parameters::kGFTTGpu(), _gpu);
2065 
2066 #if CV_MAJOR_VERSION < 3
2067  if(_gpu)
2068  {
2069  UWARN("GPU version of GFTT is not implemented for OpenCV<3! Using CPU version instead...");
2070  _gpu = false;
2071  }
2072 #endif
2073 
2074 #ifdef HAVE_OPENCV_CUDAIMGPROC
2075  if(_gpu && cv::cuda::getCudaEnabledDeviceCount() == 0)
2076  {
2077  UWARN("GPU version of GFTT not available! Using CPU version instead...");
2078  _gpu = false;
2079  }
2080 #else
2081  if(_gpu)
2082  {
2083  UWARN("GPU version of GFTT not available (OpenCV cudaimageproc module)! Using CPU version instead...");
2084  _gpu = false;
2085  }
2086 #endif
2087  if(_gpu)
2088  {
2089 #ifdef HAVE_OPENCV_CUDAIMGPROC
2090  _gpuGftt = cv::cuda::createGoodFeaturesToTrackDetector(CV_8UC1, this->getMaxFeatures(), _qualityLevel, _minDistance, _blockSize, _useHarrisDetector ,_k);
2091 #else
2092  UFATAL("not supposed to be here!");
2093 #endif
2094  }
2095  else
2096  {
2097 #if CV_MAJOR_VERSION < 3
2098  _gftt = cv::Ptr<CV_GFTT>(new CV_GFTT(this->getMaxFeatures(), _qualityLevel, _minDistance, _blockSize, _useHarrisDetector ,_k));
2099 #else
2101 #endif
2102  }
2103 }
2104 
2105 std::vector<cv::KeyPoint> GFTT::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2106 {
2107  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2108  std::vector<cv::KeyPoint> keypoints;
2109  cv::Mat imgRoi(image, roi);
2110  cv::Mat maskRoi;
2111  if(!mask.empty())
2112  {
2113  maskRoi = cv::Mat(mask, roi);
2114  }
2115 
2116 #if CV_MAJOR_VERSION >= 3 && defined(HAVE_OPENCV_CUDAIMGPROC)
2117  if(_gpu)
2118  {
2119  cv::cuda::GpuMat imgGpu(imgRoi);
2120  cv::cuda::GpuMat maskGpu(maskRoi);
2121  cv::cuda::GpuMat cornersGpu;
2122  _gpuGftt->detect(imgGpu, cornersGpu, maskGpu);
2123  std::vector<cv::Point2f> corners(cornersGpu.cols);
2124  cv::Mat cornersMat(1, cornersGpu.cols, CV_32FC2, (void*)&corners[0]);
2125  cornersGpu.download(cornersMat);
2126  cv::KeyPoint::convert(corners, keypoints, _blockSize);
2127  }
2128  else
2129 #endif
2130  {
2131  _gftt->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
2132  }
2133 
2134  return keypoints;
2135 }
2136 
2138 //FAST-BRIEF
2141  GFTT(parameters),
2142  bytes_(Parameters::defaultBRIEFBytes())
2143 {
2144  parseParameters(parameters);
2145 }
2146 
2148 {
2149 }
2150 
2152 {
2153  GFTT::parseParameters(parameters);
2154 
2155  Parameters::parse(parameters, Parameters::kBRIEFBytes(), bytes_);
2156 #if CV_MAJOR_VERSION < 3
2157  _brief = cv::Ptr<CV_BRIEF>(new CV_BRIEF(bytes_));
2158 #else
2159 #ifdef HAVE_OPENCV_XFEATURES2D
2160  _brief = CV_BRIEF::create(bytes_);
2161 #else
2162  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
2163 #endif
2164 #endif
2165 }
2166 
2167 cv::Mat GFTT_BRIEF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2168 {
2169  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2170  cv::Mat descriptors;
2171 #if CV_MAJOR_VERSION < 3
2172  _brief->compute(image, keypoints, descriptors);
2173 #else
2174 #ifdef HAVE_OPENCV_XFEATURES2D
2175  _brief->compute(image, keypoints, descriptors);
2176 #else
2177  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
2178 #endif
2179 #endif
2180  return descriptors;
2181 }
2182 
2184 //GFTT-FREAK
2187  GFTT(parameters),
2188  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2189  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2190  patternScale_(Parameters::defaultFREAKPatternScale()),
2191  nOctaves_(Parameters::defaultFREAKNOctaves())
2192 {
2193  parseParameters(parameters);
2194 }
2195 
2197 {
2198 }
2199 
2201 {
2202  GFTT::parseParameters(parameters);
2203 
2204  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2205  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2206  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2207  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2208 
2209 #if CV_MAJOR_VERSION < 3
2211 #else
2212 #ifdef HAVE_OPENCV_XFEATURES2D
2214 #else
2215  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2216 #endif
2217 #endif
2218 }
2219 
2220 cv::Mat GFTT_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2221 {
2222  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2223  cv::Mat descriptors;
2224 #if CV_MAJOR_VERSION < 3
2225  _freak->compute(image, keypoints, descriptors);
2226 #else
2227 #ifdef HAVE_OPENCV_XFEATURES2D
2228  _freak->compute(image, keypoints, descriptors);
2229 #else
2230  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2231 #endif
2232 #endif
2233  return descriptors;
2234 }
2235 
2237 //SURF-FREAK
2240  SURF(parameters),
2241  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2242  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2243  patternScale_(Parameters::defaultFREAKPatternScale()),
2244  nOctaves_(Parameters::defaultFREAKNOctaves())
2245 {
2246  parseParameters(parameters);
2247 }
2248 
2250 {
2251 }
2252 
2254 {
2255  SURF::parseParameters(parameters);
2256 
2257  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2258  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2259  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2260  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2261 
2262 #if CV_MAJOR_VERSION < 3
2264 #else
2265 #ifdef HAVE_OPENCV_XFEATURES2D
2267 #else
2268  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2269 #endif
2270 #endif
2271 }
2272 
2273 cv::Mat SURF_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2274 {
2275  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2276  cv::Mat descriptors;
2277 #if CV_MAJOR_VERSION < 3
2278  _freak->compute(image, keypoints, descriptors);
2279 #else
2280 #ifdef HAVE_OPENCV_XFEATURES2D
2281  _freak->compute(image, keypoints, descriptors);
2282 #else
2283  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2284 #endif
2285 #endif
2286  return descriptors;
2287 }
2288 
2290 //GFTT-ORB
2292 GFTT_ORB::GFTT_ORB(const ParametersMap & parameters) :
2293  GFTT(parameters),
2294  _orb(parameters)
2295 {
2296  parseParameters(parameters);
2297 }
2298 
2300 {
2301 }
2302 
2304 {
2305  GFTT::parseParameters(parameters);
2306  _orb.parseParameters(parameters);
2307 }
2308 
2309 cv::Mat GFTT_ORB::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2310 {
2311  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2312  return _orb.generateDescriptors(image, keypoints);
2313 }
2314 
2316 //BRISK
2318 BRISK::BRISK(const ParametersMap & parameters) :
2319  thresh_(Parameters::defaultBRISKThresh()),
2320  octaves_(Parameters::defaultBRISKOctaves()),
2321  patternScale_(Parameters::defaultBRISKPatternScale())
2322 {
2323  parseParameters(parameters);
2324 }
2325 
2327 {
2328 }
2329 
2330 void BRISK::parseParameters(const ParametersMap & parameters)
2331 {
2332  Feature2D::parseParameters(parameters);
2333 
2334  Parameters::parse(parameters, Parameters::kBRISKThresh(), thresh_);
2335  Parameters::parse(parameters, Parameters::kBRISKOctaves(), octaves_);
2336  Parameters::parse(parameters, Parameters::kBRISKPatternScale(), patternScale_);
2337 
2338 #if CV_MAJOR_VERSION < 3
2339  brisk_ = cv::Ptr<CV_BRISK>(new CV_BRISK(thresh_, octaves_, patternScale_));
2340 #else
2341  brisk_ = CV_BRISK::create(thresh_, octaves_, patternScale_);
2342 #endif
2343 }
2344 
2345 std::vector<cv::KeyPoint> BRISK::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2346 {
2347  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2348  std::vector<cv::KeyPoint> keypoints;
2349  cv::Mat imgRoi(image, roi);
2350  cv::Mat maskRoi;
2351  if(!mask.empty())
2352  {
2353  maskRoi = cv::Mat(mask, roi);
2354  }
2355  brisk_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
2356  return keypoints;
2357 }
2358 
2359 cv::Mat BRISK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2360 {
2361  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2362  cv::Mat descriptors;
2363  brisk_->compute(image, keypoints, descriptors);
2364  return descriptors;
2365 }
2366 
2368 //KAZE
2370 KAZE::KAZE(const ParametersMap & parameters) :
2371  extended_(Parameters::defaultKAZEExtended()),
2372  upright_(Parameters::defaultKAZEUpright()),
2373  threshold_(Parameters::defaultKAZEThreshold()),
2374  nOctaves_(Parameters::defaultKAZENOctaves()),
2375  nOctaveLayers_(Parameters::defaultKAZENOctaveLayers()),
2376  diffusivity_(Parameters::defaultKAZEDiffusivity())
2377 {
2378  parseParameters(parameters);
2379 }
2380 
2382 {
2383 }
2384 
2385 void KAZE::parseParameters(const ParametersMap & parameters)
2386 {
2387  Feature2D::parseParameters(parameters);
2388 
2389  Parameters::parse(parameters, Parameters::kKAZEExtended(), extended_);
2390  Parameters::parse(parameters, Parameters::kKAZEUpright(), upright_);
2391  Parameters::parse(parameters, Parameters::kKAZEThreshold(), threshold_);
2392  Parameters::parse(parameters, Parameters::kKAZENOctaves(), nOctaves_);
2393  Parameters::parse(parameters, Parameters::kKAZENOctaveLayers(), nOctaveLayers_);
2394  Parameters::parse(parameters, Parameters::kKAZEDiffusivity(), diffusivity_);
2395 
2396 #if CV_MAJOR_VERSION > 3
2397  kaze_ = cv::KAZE::create(extended_, upright_, threshold_, nOctaves_, nOctaveLayers_, (cv::KAZE::DiffusivityType)diffusivity_);
2398 #elif CV_MAJOR_VERSION > 2
2399  kaze_ = cv::KAZE::create(extended_, upright_, threshold_, nOctaves_, nOctaveLayers_, diffusivity_);
2400 #else
2401  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2402 #endif
2403 }
2404 
2405 std::vector<cv::KeyPoint> KAZE::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2406 {
2407  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2408  std::vector<cv::KeyPoint> keypoints;
2409 #if CV_MAJOR_VERSION > 2
2410  cv::Mat imgRoi(image, roi);
2411  cv::Mat maskRoi;
2412  if (!mask.empty())
2413  {
2414  maskRoi = cv::Mat(mask, roi);
2415  }
2416  kaze_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
2417 #else
2418  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2419 #endif
2420  return keypoints;
2421 }
2422 
2423 cv::Mat KAZE::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2424 {
2425  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2426  cv::Mat descriptors;
2427 #if CV_MAJOR_VERSION > 2
2428  kaze_->compute(image, keypoints, descriptors);
2429 #else
2430  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2431 #endif
2432  return descriptors;
2433 }
2434 
2436 //ORBOctree
2439  scaleFactor_(Parameters::defaultORBScaleFactor()),
2440  nLevels_(Parameters::defaultORBNLevels()),
2441  patchSize_(Parameters::defaultORBPatchSize()),
2442  edgeThreshold_(Parameters::defaultORBEdgeThreshold()),
2443  fastThreshold_(Parameters::defaultFASTThreshold()),
2444  fastMinThreshold_(Parameters::defaultFASTMinThreshold())
2445 {
2446  parseParameters(parameters);
2447 }
2448 
2450 {
2451 }
2452 
2454 {
2455  Feature2D::parseParameters(parameters);
2456 
2457  Parameters::parse(parameters, Parameters::kORBScaleFactor(), scaleFactor_);
2458  Parameters::parse(parameters, Parameters::kORBNLevels(), nLevels_);
2459  Parameters::parse(parameters, Parameters::kORBPatchSize(), patchSize_);
2460  Parameters::parse(parameters, Parameters::kORBEdgeThreshold(), edgeThreshold_);
2461 
2462  Parameters::parse(parameters, Parameters::kFASTThreshold(), fastThreshold_);
2463  Parameters::parse(parameters, Parameters::kFASTMinThreshold(), fastMinThreshold_);
2464 
2465 #ifdef RTABMAP_ORB_OCTREE
2467 #else
2468  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2469 #endif
2470 }
2471 
2472 std::vector<cv::KeyPoint> ORBOctree::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2473 {
2474  std::vector<cv::KeyPoint> keypoints;
2475  descriptors_ = cv::Mat();
2476 #ifdef RTABMAP_ORB_OCTREE
2477  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2478  cv::Mat imgRoi(image, roi);
2479  cv::Mat maskRoi;
2480  if(!mask.empty())
2481  {
2482  maskRoi = cv::Mat(mask, roi);
2483  }
2484 
2485  (*_orb)(imgRoi, maskRoi, keypoints, descriptors_);
2486 
2487  // OrbOctree ignores the mask, so we have to apply it manually here
2488  if(!keypoints.empty() && !maskRoi.empty())
2489  {
2490  std::vector<cv::KeyPoint> validKeypoints;
2491  validKeypoints.reserve(keypoints.size());
2492  cv::Mat validDescriptors;
2493  for(size_t i=0; i<keypoints.size(); ++i)
2494  {
2495  if(maskRoi.at<unsigned char>(keypoints[i].pt.y+roi.y, keypoints[i].pt.x+roi.x) != 0)
2496  {
2497  validKeypoints.push_back(keypoints[i]);
2498  validDescriptors.push_back(descriptors_.row(i));
2499  }
2500  }
2501  keypoints = validKeypoints;
2502  descriptors_ = validDescriptors;
2503  }
2504 
2505  if((int)keypoints.size() > this->getMaxFeatures())
2506  {
2507  limitKeypoints(keypoints, descriptors_, this->getMaxFeatures(), roi.size(), this->getSSC());
2508  }
2509 #else
2510  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2511 #endif
2512  return keypoints;
2513 }
2514 
2515 cv::Mat ORBOctree::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2516 {
2517 #ifdef RTABMAP_ORB_OCTREE
2518  UASSERT_MSG((int)keypoints.size() == descriptors_.rows, uFormat("keypoints=%d descriptors=%d", (int)keypoints.size(), descriptors_.rows).c_str());
2519 #else
2520  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2521 #endif
2522  return descriptors_;
2523 }
2524 
2526 //SuperPointTorch
2529  path_(Parameters::defaultSuperPointModelPath()),
2530  threshold_(Parameters::defaultSuperPointThreshold()),
2531  nms_(Parameters::defaultSuperPointNMS()),
2532  minDistance_(Parameters::defaultSuperPointNMSRadius()),
2533  cuda_(Parameters::defaultSuperPointCuda())
2534 {
2535  parseParameters(parameters);
2536 }
2537 
2539 {
2540 }
2541 
2543 {
2544  Feature2D::parseParameters(parameters);
2545 
2546  std::string previousPath = path_;
2547 #ifdef RTABMAP_TORCH
2548  bool previousCuda = cuda_;
2549 #endif
2550  Parameters::parse(parameters, Parameters::kSuperPointModelPath(), path_);
2551  Parameters::parse(parameters, Parameters::kSuperPointThreshold(), threshold_);
2552  Parameters::parse(parameters, Parameters::kSuperPointNMS(), nms_);
2553  Parameters::parse(parameters, Parameters::kSuperPointNMSRadius(), minDistance_);
2554  Parameters::parse(parameters, Parameters::kSuperPointCuda(), cuda_);
2555 
2556 #ifdef RTABMAP_TORCH
2557  if(superPoint_.get() == 0 || path_.compare(previousPath) != 0 || previousCuda != cuda_)
2558  {
2559  superPoint_ = cv::Ptr<SPDetector>(new SPDetector(path_, threshold_, nms_, minDistance_, cuda_));
2560  }
2561  else
2562  {
2563  superPoint_->setThreshold(threshold_);
2564  superPoint_->SetNMS(nms_);
2565  superPoint_->setMinDistance(minDistance_);
2566  }
2567 #else
2568  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2569 #endif
2570 }
2571 
2572 std::vector<cv::KeyPoint> SuperPointTorch::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2573 {
2574 #ifdef RTABMAP_TORCH
2575  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2576  if(roi.x!=0 || roi.y !=0)
2577  {
2578  UERROR("SuperPoint: Not supporting ROI (%d,%d,%d,%d). Make sure %s, %s, %s, %s, %s, %s are all set to default values.",
2579  roi.x, roi.y, roi.width, roi.height,
2580  Parameters::kKpRoiRatios().c_str(),
2581  Parameters::kVisRoiRatios().c_str(),
2582  Parameters::kVisGridRows().c_str(),
2583  Parameters::kVisGridCols().c_str(),
2584  Parameters::kKpGridRows().c_str(),
2585  Parameters::kKpGridCols().c_str());
2586  return std::vector<cv::KeyPoint>();
2587  }
2588  return superPoint_->detect(image, mask);
2589 #else
2590  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2591  return std::vector<cv::KeyPoint>();
2592 #endif
2593 }
2594 
2595 cv::Mat SuperPointTorch::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2596 {
2597 #ifdef RTABMAP_TORCH
2598  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2599  return superPoint_->compute(keypoints);
2600 #else
2601  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2602  return cv::Mat();
2603 #endif
2604 }
2605 
2606 
2608 //GFTT-DAISY
2611  GFTT(parameters),
2612  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2613  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2614  patternScale_(Parameters::defaultFREAKPatternScale()),
2615  nOctaves_(Parameters::defaultFREAKNOctaves())
2616 {
2617  parseParameters(parameters);
2618 }
2619 
2621 {
2622 }
2623 
2625 {
2626  GFTT::parseParameters(parameters);
2627 
2628  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2629  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2630  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2631  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2632 
2633 #ifdef HAVE_OPENCV_XFEATURES2D
2634  _daisy = CV_DAISY::create();
2635 #else
2636  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2637 #endif
2638 }
2639 
2640 cv::Mat GFTT_DAISY::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2641 {
2642  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2643  cv::Mat descriptors;
2644 #ifdef HAVE_OPENCV_XFEATURES2D
2645  _daisy->compute(image, keypoints, descriptors);
2646 #else
2647  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2648 #endif
2649  return descriptors;
2650 }
2651 
2653 //SURF-DAISY
2656  SURF(parameters),
2657  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2658  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2659  patternScale_(Parameters::defaultFREAKPatternScale()),
2660  nOctaves_(Parameters::defaultFREAKNOctaves())
2661 {
2662  parseParameters(parameters);
2663 }
2664 
2666 {
2667 }
2668 
2670 {
2671  SURF::parseParameters(parameters);
2672 
2673  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2674  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2675  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2676  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2677 
2678 #ifdef HAVE_OPENCV_XFEATURES2D
2679  _daisy = CV_DAISY::create();
2680 #else
2681  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2682 #endif
2683 }
2684 
2685 cv::Mat SURF_DAISY::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2686 {
2687  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2688  cv::Mat descriptors;
2689 #ifdef HAVE_OPENCV_XFEATURES2D
2690  _daisy->compute(image, keypoints, descriptors);
2691 #else
2692  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2693 #endif
2694  return descriptors;
2695 }
2696 
2697 }
rtabmap::SensorData
Definition: SensorData.h:51
w
RowVector3d w
glm::min
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
int
int
rtabmap::Feature2D::filterKeypointsByDisparity
static void filterKeypointsByDisparity(std::vector< cv::KeyPoint > &keypoints, const cv::Mat &disparity, float minDisparity)
Definition: Features2d.cpp:211
rtabmap::FAST_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:420
rtabmap::ORB::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:1620
rtabmap::GFTT_BRIEF::bytes_
int bytes_
Definition: Features2d.h:465
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:1152
glm::log2
GLM_FUNC_DECL genType log2(genType x)
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:2105
rtabmap::util2d::computeRoi
cv::Rect RTABMAP_CORE_EXPORT computeRoi(const cv::Mat &image, const std::string &roiRatios)
Definition: util2d.cpp:1113
rtabmap::Stereo::isGpuEnabled
virtual bool isGpuEnabled() const
Definition: Stereo.h:66
rtabmap::GFTT_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:484
rtabmap::Feature2D::create
static Feature2D * create(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:608
rtabmap::ORBOctree::patchSize_
int patchSize_
Definition: Features2d.h:597
rtabmap::GFTT_ORB::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2309
rtabmap::FAST::gridCols_
int gridCols_
Definition: Features2d.h:372
rtabmap::Feature2D::~Feature2D
virtual ~Feature2D()
Definition: Features2d.cpp:543
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:92
glm::mask
GLM_FUNC_DECL genIType mask(genIType const &count)
rtabmap::ORB::_orb
cv::Ptr< CV_ORB > _orb
Definition: Features2d.h:346
rtabmap::Feature2D::generateKeypoints
std::vector< cv::KeyPoint > generateKeypoints(const cv::Mat &image, const cv::Mat &mask=cv::Mat())
Definition: Features2d.cpp:767
rtabmap::GFTT::_gpuGftt
cv::Ptr< CV_GFTT_GPU > _gpuGftt
Definition: Features2d.h:448
rtabmap::KAZE::extended_
bool extended_
Definition: Features2d.h:568
rtabmap::ORBOctree::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2453
rtabmap::Feature2D::kFeaturePyDetector
@ kFeaturePyDetector
Definition: Features2d.h:132
rtabmap::FAST::~FAST
virtual ~FAST()
Definition: Features2d.cpp:1733
rtabmap::GFTT_DAISY::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:644
rtabmap::FAST_BRIEF::bytes_
int bytes_
Definition: Features2d.h:400
rtabmap::FAST::fastCVCornerScores_
uint32_t * fastCVCornerScores_
Definition: Features2d.h:379
rtabmap::SURF_FREAK::SURF_FREAK
SURF_FREAK(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2239
rtabmap::ORBOctree
Definition: Features2d.h:581
rtabmap::GFTT_ORB::_orb
ORB _orb
Definition: Features2d.h:528
rtabmap::BRISK::~BRISK
virtual ~BRISK()
Definition: Features2d.cpp:2326
rtabmap::Feature2D::kFeatureGfttBrief
@ kFeatureGfttBrief
Definition: Features2d.h:123
rtabmap::FAST_BRIEF
Definition: Features2d.h:387
timer
rtabmap::SURF::nOctaves_
int nOctaves_
Definition: Features2d.h:275
rtabmap::GFTT::_useHarrisDetector
bool _useHarrisDetector
Definition: Features2d.h:443
rtabmap::GFTT_FREAK::~GFTT_FREAK
virtual ~GFTT_FREAK()
Definition: Features2d.cpp:2196
rtabmap::FAST
Definition: Features2d.h:351
rtabmap::GFTT_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:487
rtabmap::SuperPointTorch::superPoint_
cv::Ptr< SPDetector > superPoint_
Definition: Features2d.h:620
rtabmap::ORBOctree::_orb
cv::Ptr< ORBextractor > _orb
Definition: Features2d.h:602
CV_FREAK
cv::FREAK CV_FREAK
Definition: Features2d.h:55
rtabmap::Feature2D::kFeatureFastFreak
@ kFeatureFastFreak
Definition: Features2d.h:120
rtabmap::FAST::maxThreshold_
int maxThreshold_
Definition: Features2d.h:370
rtabmap::SURF::SURF
SURF(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1093
rtabmap::ORB::patchSize_
int patchSize_
Definition: Features2d.h:340
rtabmap::ORB::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1507
uint32_t
::uint32_t uint32_t
rtabmap::SURF_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:511
size
Index size
rtabmap::SURF::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:276
this
this
ORBextractor.h
rtabmap::BRISK::BRISK
BRISK(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2318
rtabmap::KAZE::nOctaves_
int nOctaves_
Definition: Features2d.h:571
rtabmap::ORBOctree::nLevels_
int nLevels_
Definition: Features2d.h:596
rtabmap::GFTT_DAISY::GFTT_DAISY
GFTT_DAISY(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2610
rtabmap::SIFT::gpu_
bool gpu_
Definition: Features2d.h:307
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::SIFT::upscale_
bool upscale_
Definition: Features2d.h:309
rtabmap::SURF_FREAK::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2273
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:2253
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:2345
util3d_features.h
rtabmap::Stereo
Definition: Stereo.h:38
ULogger::kDebug
@ kDebug
Definition: ULogger.h:252
rtabmap::ORB::scaleFactor_
float scaleFactor_
Definition: Features2d.h:334
rtabmap::GFTT_BRIEF::_brief
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:467
rtabmap::SURF
Definition: Features2d.h:260
rtabmap::KAZE::threshold_
float threshold_
Definition: Features2d.h:570
threshold_
Index threshold_
type
rtabmap::FAST_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:419
rtabmap::BRISK
Definition: Features2d.h:532
CV_SIFT
cv::SIFT CV_SIFT
Definition: Features2d.h:52
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:1842
rtabmap::ORBOctree::fastMinThreshold_
int fastMinThreshold_
Definition: Features2d.h:600
rtabmap::GFTT::_qualityLevel
double _qualityLevel
Definition: Features2d.h:440
rtabmap::GFTT::_gftt
cv::Ptr< CV_GFTT > _gftt
Definition: Features2d.h:447
CV_BRISK
cv::BRISK CV_BRISK
Definition: Features2d.h:58
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:278
h
const double h
rtabmap::FAST::fastCVLastImageHeight_
int fastCVLastImageHeight_
Definition: Features2d.h:377
corners
void corners(const MatrixType &m)
rtabmap::Feature2D::_subPixIterations
int _subPixIterations
Definition: Features2d.h:251
rtabmap::ORBextractor
Definition: ORBextractor.h:53
util3d.h
rtabmap::SURF::hessianThreshold_
double hessianThreshold_
Definition: Features2d.h:274
rtabmap::FAST::FAST
FAST(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1680
rtabmap::SIFT::preciseUpscale_
bool preciseUpscale_
Definition: Features2d.h:305
rtabmap::SIFT::sigma_
double sigma_
Definition: Features2d.h:304
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:347
rtabmap::Feature2D::kFeatureSift
@ kFeatureSift
Definition: Features2d.h:118
rtabmap::FAST_FREAK::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2021
rtabmap::FAST::gpuKeypointsRatio_
double gpuKeypointsRatio_
Definition: Features2d.h:368
UTimer.h
ULOGGER_DEBUG
#define ULOGGER_DEBUG(...)
Definition: ULogger.h:53
rtabmap::BRISK::octaves_
int octaves_
Definition: Features2d.h:547
rtabmap::Feature2D::generateDescriptors
cv::Mat generateDescriptors(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:872
rtabmap::Feature2D::kFeatureFastBrief
@ kFeatureFastBrief
Definition: Features2d.h:121
rtabmap::GFTT_BRIEF::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2167
UMath.h
Basic mathematics functions.
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:503
rtabmap::KAZE::~KAZE
virtual ~KAZE()
Definition: Features2d.cpp:2381
desc
desc
rtabmap::Feature2D::kFeatureGfttOrb
@ kFeatureGfttOrb
Definition: Features2d.h:125
rtabmap::BRISK::thresh_
int thresh_
Definition: Features2d.h:546
rtabmap::GFTT_FREAK::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2200
fabs
Real fabs(const Real &a)
rtabmap::ORB::nLevels_
int nLevels_
Definition: Features2d.h:335
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:1186
rtabmap::SIFT::cudaSiftDescriptors_
cv::Mat cudaSiftDescriptors_
Definition: Features2d.h:315
rtabmap::SURF::_gpuSurf
cv::Ptr< CV_SURF_GPU > _gpuSurf
Definition: Features2d.h:283
SuperPoint.h
rtabmap::GFTT_BRIEF::GFTT_BRIEF
GFTT_BRIEF(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2140
rtabmap::Feature2D::computeRoi
static cv::Rect computeRoi(const cv::Mat &image, const std::string &roiRatios)
Definition: Features2d.cpp:515
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:253
rtabmap::ORB::~ORB
virtual ~ORB()
Definition: Features2d.cpp:1503
rtabmap::FAST_FREAK
Definition: Features2d.h:406
UFATAL
#define UFATAL(...)
rtabmap::GFTT_ORB::~GFTT_ORB
virtual ~GFTT_ORB()
Definition: Features2d.cpp:2299
rtabmap::SURF_DAISY::SURF_DAISY
SURF_DAISY(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2655
rtabmap::GFTT_DAISY::patternScale_
float patternScale_
Definition: Features2d.h:645
rtabmap::ORB::gpu_
bool gpu_
Definition: Features2d.h:341
rtabmap::Feature2D::kFeatureSurfDaisy
@ kFeatureSurfDaisy
Definition: Features2d.h:131
rtabmap::FAST_FREAK::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2001
rtabmap::GFTT_BRIEF::~GFTT_BRIEF
virtual ~GFTT_BRIEF()
Definition: Features2d.cpp:2147
rtabmap::SURF_DAISY::~SURF_DAISY
virtual ~SURF_DAISY()
Definition: Features2d.cpp:2665
uint16_t
::uint16_t uint16_t
data
int data[]
rtabmap::FAST_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:422
rtabmap::Stereo::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Stereo.cpp:65
rtabmap::SURF_FREAK::~SURF_FREAK
virtual ~SURF_FREAK()
Definition: Features2d.cpp:2249
rtabmap::FAST::gpu_
bool gpu_
Definition: Features2d.h:367
rtabmap::Feature2D::kFeatureOrb
@ kFeatureOrb
Definition: Features2d.h:119
Features2d.h
rtabmap::SURF_DAISY::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2685
rtabmap::KAZE::diffusivity_
int diffusivity_
Definition: Features2d.h:573
j
std::ptrdiff_t j
rtabmap::PyDetector
Definition: PyDetector.h:20
rtabmap::SIFT::~SIFT
virtual ~SIFT()
Definition: Features2d.cpp:1244
rtabmap::ORB::scoreType_
int scoreType_
Definition: Features2d.h:339
rtabmap::Feature2D::gridCols_
int gridCols_
Definition: Features2d.h:254
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:2640
UConversion.h
Some conversion functions.
rtabmap::SIFT::SIFT
SIFT(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1227
rtabmap::FAST_BRIEF::FAST_BRIEF
FAST_BRIEF(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1941
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:1948
rtabmap::Feature2D::kFeatureSurfFreak
@ kFeatureSurfFreak
Definition: Features2d.h:129
rtabmap::KAZE::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2423
rtabmap::SIFT
Definition: Features2d.h:287
rtabmap::GFTT::GFTT
GFTT(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2040
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:2572
CV_SURF
cv::SURF CV_SURF
Definition: Features2d.h:53
rtabmap::KAZE::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:572
CV_FAST
cv::FastFeatureDetector CV_FAST
Definition: Features2d.h:54
rtabmap::Feature2D::getMaxFeatures
int getMaxFeatures() const
Definition: Features2d.h:212
ULogger::kWarning
@ kWarning
Definition: ULogger.h:252
rtabmap::util3d::isFinite
bool RTABMAP_CORE_EXPORT isFinite(const cv::Point3f &pt)
Definition: util3d.cpp:3436
rtabmap::GFTT_ORB::GFTT_ORB
GFTT_ORB(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2292
rtabmap::ORB::fastThreshold_
int fastThreshold_
Definition: Features2d.h:343
glm::max
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
rtabmap::util2d::SSC
std::vector< int > RTABMAP_CORE_EXPORT SSC(const std::vector< cv::KeyPoint > &keypoints, int maxKeypoints, float tolerance, int cols, int rows, const std::vector< int > &indx={})
Definition: util2d.cpp:2205
rtabmap::Feature2D::_minDepth
float _minDepth
Definition: Features2d.h:248
rtabmap::Feature2D::_stereo
Stereo * _stereo
Definition: Features2d.h:256
rtabmap::GFTT_DAISY::nOctaves_
int nOctaves_
Definition: Features2d.h:646
rtabmap::Feature2D::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:547
rtabmap::FAST::fastCV_
int fastCV_
Definition: Features2d.h:373
rtabmap::SuperPointTorch
Definition: Features2d.h:607
rtabmap::Feature2D::kFeatureSuperPointTorch
@ kFeatureSuperPointTorch
Definition: Features2d.h:128
CV_BRIEF
cv::BriefDescriptorExtractor CV_BRIEF
Definition: Features2d.h:57
rtabmap::GFTT_ORB
Definition: Features2d.h:515
rtabmap::SuperPointTorch::nms_
bool nms_
Definition: Features2d.h:624
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:1313
rtabmap::BRISK::brisk_
cv::Ptr< CV_BRISK > brisk_
Definition: Features2d.h:550
rtabmap::FAST::_fast
cv::Ptr< cv::FeatureDetector > _fast
Definition: Features2d.h:382
rtabmap::ORBOctree::~ORBOctree
virtual ~ORBOctree()
Definition: Features2d.cpp:2449
rtabmap::SuperPointTorch::~SuperPointTorch
virtual ~SuperPointTorch()
Definition: Features2d.cpp:2538
UASSERT
#define UASSERT(condition)
d
d
rtabmap::FAST_FREAK::~FAST_FREAK
virtual ~FAST_FREAK()
Definition: Features2d.cpp:1997
rtabmap::Feature2D
Definition: Features2d.h:114
rtabmap::SURF::extended_
bool extended_
Definition: Features2d.h:277
rtabmap::SuperPointTorch::path_
std::string path_
Definition: Features2d.h:622
rtabmap::SuperPointTorch::minDistance_
int minDistance_
Definition: Features2d.h:625
rtabmap::Feature2D::Type
Type
Definition: Features2d.h:116
x
x
rtabmap::KAZE::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2385
rtabmap::GFTT_DAISY::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2624
rtabmap::SIFT::rootSIFT_
bool rootSIFT_
Definition: Features2d.h:306
rtabmap::Feature2D::getType
virtual Feature2D::Type getType() const =0
Stereo.h
rtabmap::BRISK::patternScale_
float patternScale_
Definition: Features2d.h:548
rtabmap::GFTT_DAISY::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:643
rtabmap::GFTT_BRIEF::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2151
rtabmap::SURF_DAISY
Definition: Features2d.h:654
rtabmap::FAST::minThreshold_
int minThreshold_
Definition: Features2d.h:369
rtabmap::Parameters
Definition: Parameters.h:170
rtabmap::FAST_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:421
rtabmap::SuperPointTorch::threshold_
float threshold_
Definition: Features2d.h:623
rtabmap::SIFT::cudaSiftUpscaling_
bool cudaSiftUpscaling_
Definition: Features2d.h:316
rtabmap::SuperPointTorch::SuperPointTorch
SuperPointTorch(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2528
rtabmap::GFTT_FREAK::GFTT_FREAK
GFTT_FREAK(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2186
rtabmap::FAST::nonmaxSuppression_
bool nonmaxSuppression_
Definition: Features2d.h:366
rtabmap::Feature2D::kFeatureBrisk
@ kFeatureBrisk
Definition: Features2d.h:124
rtabmap::SIFT::contrastThreshold_
double contrastThreshold_
Definition: Features2d.h:302
rtabmap::GFTT_FREAK::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2220
rtabmap::SIFT::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1257
rtabmap::Feature2D::_maxDepth
float _maxDepth
Definition: Features2d.h:247
rtabmap::GFTT::_gpu
bool _gpu
Definition: Features2d.h:445
UASSERT_MSG
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
UWARN
#define UWARN(...)
rtabmap::SURF_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:507
rtabmap::SuperPointTorch::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2595
rtabmap::SPDetector
Definition: SuperPoint.h:49
rtabmap::GFTT_BRIEF
Definition: Features2d.h:452
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:669
ULogger::level
static ULogger::Level level()
Definition: ULogger.h:340
rtabmap::SIFT::cudaSiftMemorySize_
cv::Size cudaSiftMemorySize_
Definition: Features2d.h:314
glm::log
GLM_FUNC_DECL genType log(genType const &x)
rtabmap::Feature2D::_roiRatios
std::vector< float > _roiRatios
Definition: Features2d.h:249
rtabmap::SIFT::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:1439
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
rtabmap::GFTT::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2055
rtabmap::Feature2D::generateKeypoints3D
std::vector< cv::Point3f > generateKeypoints3D(const SensorData &data, const std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:888
ULogger.h
ULogger class and convenient macros.
rtabmap::Feature2D::kFeatureGfttFreak
@ kFeatureGfttFreak
Definition: Features2d.h:122
rtabmap::SURF::_surf
cv::Ptr< CV_SURF > _surf
Definition: Features2d.h:282
rtabmap::SURF::~SURF
virtual ~SURF()
Definition: Features2d.cpp:1105
rtabmap::KAZE::upright_
bool upright_
Definition: Features2d.h:569
rtabmap::FAST::fastCVCorners_
uint32_t * fastCVCorners_
Definition: Features2d.h:378
rtabmap::GFTT
Definition: Features2d.h:428
CV_SURF_GPU
cv::gpu::SURF_GPU CV_SURF_GPU
Definition: Features2d.h:59
rtabmap::GFTT_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:486
empty
rtabmap::SIFT::cudaSiftMemory_
float * cudaSiftMemory_
Definition: Features2d.h:313
util2d.h
rtabmap::Feature2D::parameters_
ParametersMap parameters_
Definition: Features2d.h:244
rtabmap::SURF_FREAK::patternScale_
float patternScale_
Definition: Features2d.h:508
rtabmap::SURF::gpuKeypointsRatio_
float gpuKeypointsRatio_
Definition: Features2d.h:279
uSplit
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:564
rtabmap::Feature2D::_subPixWinSize
int _subPixWinSize
Definition: Features2d.h:250
rtabmap::SURF_DAISY::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:667
rtabmap::GFTT_DAISY::~GFTT_DAISY
virtual ~GFTT_DAISY()
Definition: Features2d.cpp:2620
rtabmap::SURF_DAISY::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:668
rtabmap::KAZE::KAZE
KAZE(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2370
rtabmap::SIFT::edgeThreshold_
double edgeThreshold_
Definition: Features2d.h:303
rtabmap::FAST_BRIEF::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1952
rtabmap::ORB::edgeThreshold_
int edgeThreshold_
Definition: Features2d.h:336
CV_ORB_GPU
cv::gpu::ORB_GPU CV_ORB_GPU
Definition: Features2d.h:60
iter
iterator iter(handle obj)
rtabmap::GFTT_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:489
ULOGGER_ERROR
#define ULOGGER_ERROR(...)
Definition: ULogger.h:56
std
rtabmap::ORBOctree::scaleFactor_
float scaleFactor_
Definition: Features2d.h:595
rtabmap::FAST::fastCVMaxFeatures_
int fastCVMaxFeatures_
Definition: Features2d.h:376
c_str
const char * c_str(Args &&...args)
rtabmap::BRISK::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2330
UStl.h
Wrappers of STL for convenient functions.
rtabmap::Feature2D::kFeatureKaze
@ kFeatureKaze
Definition: Features2d.h:126
rtabmap::ORBOctree::ORBOctree
ORBOctree(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2438
rtabmap::SURF_FREAK::nOctaves_
int nOctaves_
Definition: Features2d.h:509
rtabmap::GFTT_DAISY
Definition: Features2d.h:630
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:2405
v
Array< int, Dynamic, 1 > v
UDEBUG
#define UDEBUG(...)
rtabmap::ORB::WTA_K_
int WTA_K_
Definition: Features2d.h:338
rtabmap::ORB::nonmaxSuppresion_
bool nonmaxSuppresion_
Definition: Features2d.h:344
rtabmap::Feature2D::SSC_
bool SSC_
Definition: Features2d.h:246
rtabmap::FAST::gridRows_
int gridRows_
Definition: Features2d.h:371
rtabmap::ORBOctree::fastThreshold_
int fastThreshold_
Definition: Features2d.h:599
rtabmap::GFTT::~GFTT
virtual ~GFTT()
Definition: Features2d.cpp:2051
UTimer
Definition: UTimer.h:46
rtabmap::ORBOctree::descriptors_
cv::Mat descriptors_
Definition: Features2d.h:603
rtabmap::Stereo::create
static Stereo * create(const ParametersMap &parameters=ParametersMap())
Definition: Stereo.cpp:39
rtabmap::Feature2D::kFeatureGfttDaisy
@ kFeatureGfttDaisy
Definition: Features2d.h:130
rtabmap::Feature2D::Feature2D
Feature2D(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:528
rtabmap::GFTT_FREAK::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:485
float
float
rtabmap::SURF_DAISY::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2669
rtabmap::GFTT::_k
double _k
Definition: Features2d.h:444
rtabmap::FAST::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1750
rtabmap::FAST::threshold_
int threshold_
Definition: Features2d.h:365
rtabmap::SuperPointTorch::cuda_
bool cuda_
Definition: Features2d.h:626
rtabmap::FAST_BRIEF::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:1968
rtabmap::Feature2D::maxFeatures_
int maxFeatures_
Definition: Features2d.h:245
rtabmap::SURF::gpuVersion_
bool gpuVersion_
Definition: Features2d.h:280
rtabmap::ORBOctree::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2515
CV_GFTT
cv::GFTTDetector CV_GFTT
Definition: Features2d.h:56
rtabmap::ORB
Definition: Features2d.h:320
rtabmap::SIFT::nOctaveLayers_
int nOctaveLayers_
Definition: Features2d.h:301
rtabmap::GFTT::_blockSize
int _blockSize
Definition: Features2d.h:442
NULL
#define NULL
false
#define false
Definition: ConvertUTF.c:56
rtabmap::SURF_FREAK
Definition: Features2d.h:493
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:2472
rtabmap::ORB::ORB
ORB(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1488
rtabmap::SURF_DAISY::nOctaves_
int nOctaves_
Definition: Features2d.h:670
rtabmap::Stereo::maxDisparity
float maxDisparity() const
Definition: Stereo.h:64
rtabmap::FAST_FREAK::_freak
cv::Ptr< CV_FREAK > _freak
Definition: Features2d.h:424
rtabmap::GFTT_ORB::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2303
uStr2Float
float UTILITE_EXPORT uStr2Float(const std::string &str)
Definition: UConversion.cpp:138
rtabmap::SURF::upright_
bool upright_
Definition: Features2d.h:278
rtabmap::SIFT::sift_
cv::Ptr< CV_SIFT > sift_
Definition: Features2d.h:311
rtabmap::BRISK::generateDescriptorsImpl
virtual cv::Mat generateDescriptorsImpl(const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
Definition: Features2d.cpp:2359
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::ORB::firstLevel_
int firstLevel_
Definition: Features2d.h:337
rtabmap::SIFT::cudaSiftData_
SiftData * cudaSiftData_
Definition: Features2d.h:312
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:76
rtabmap::SuperPointTorch::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2542
UERROR
#define UERROR(...)
rtabmap::FAST_BRIEF::_brief
cv::Ptr< CV_BRIEF > _brief
Definition: Features2d.h:402
rtabmap::ORBOctree::edgeThreshold_
int edgeThreshold_
Definition: Features2d.h:598
rtabmap::KAZE
Definition: Features2d.h:554
rtabmap::SURF_FREAK::orientationNormalized_
bool orientationNormalized_
Definition: Features2d.h:506
rtabmap::GFTT_FREAK
Definition: Features2d.h:471
rtabmap::GFTT::_minDistance
double _minDistance
Definition: Features2d.h:441
value
value
rtabmap::Feature2D::_subPixEps
double _subPixEps
Definition: Features2d.h:252
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:383
rtabmap::SURF::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1109
rtabmap::FAST::fastCVTempBuf_
void * fastCVTempBuf_
Definition: Features2d.h:380
rtabmap::FAST_FREAK::FAST_FREAK
FAST_FREAK(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1987
CV_FAST_GPU
cv::gpu::FAST_GPU CV_FAST_GPU
Definition: Features2d.h:61
rtabmap::SIFT::guaussianThreshold_
float guaussianThreshold_
Definition: Features2d.h:308
rtabmap::FAST::fastCVinit_
bool fastCVinit_
Definition: Features2d.h:375
rtabmap::Feature2D::kFeatureSurf
@ kFeatureSurf
Definition: Features2d.h:117
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:1578
PyDetector.h
rtabmap::Feature2D::kFeatureOrbOctree
@ kFeatureOrbOctree
Definition: Features2d.h:127


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Feb 13 2025 03:44:53