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 if not already
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 
918  d_imageRight = data.depthOrRightRawGpu();
919  if(d_imageRight.empty()) {
920  d_imageRight = cv::cuda::GpuMat(imageRight);
921  }
922  // convert to grayscale if not already
923  if(d_imageRight.channels() > 1) {
924  cv::cuda::GpuMat tmp;
925  cv::cuda::cvtColor(d_imageRight, tmp, cv::COLOR_BGR2GRAY);
926  d_imageRight = tmp;
927  }
928  }
929  else
930 #endif
931  {
932  // convert to grayscale
933  if(imageLeft.channels() > 1)
934  {
935  cv::cvtColor(data.imageRaw(), imageLeft, cv::COLOR_BGR2GRAY);
936  }
937  if(imageRight.channels() > 1)
938  {
939  cv::cvtColor(data.rightRaw(), imageRight, cv::COLOR_BGR2GRAY);
940  }
941  }
942 
943  std::vector<cv::Point2f> leftCorners;
944  cv::KeyPoint::convert(keypoints, leftCorners);
945 
946  std::vector<cv::Point2f> rightCorners;
947 
948  if(data.stereoCameraModels().size() == 1)
949  {
950  std::vector<unsigned char> status;
951 #ifdef HAVE_OPENCV_CUDEV
952  if(_stereo->isGpuEnabled())
953  {
954  rightCorners = _stereo->computeCorrespondences(
955  d_imageLeft,
956  d_imageRight,
957  leftCorners,
958  status);
959  }
960  else
961 #endif
962  {
963  rightCorners = _stereo->computeCorrespondences(
964  imageLeft,
965  imageRight,
966  leftCorners,
967  status);
968  }
969 
971  {
972  int rejected = 0;
973  for(size_t i=0; i<status.size(); ++i)
974  {
975  if(status[i]==0)
976  {
977  ++rejected;
978  }
979  }
980  if(rejected > (int)status.size()/2)
981  {
982  UWARN("A large number (%d/%d) of stereo correspondences are rejected! "
983  "Optical flow may have failed because images are not calibrated, "
984  "the background is too far (no disparity between the images), "
985  "maximum disparity may be too small (%f) or that exposure between "
986  "left and right images is too different.",
987  rejected,
988  (int)status.size(),
989  _stereo->maxDisparity());
990  }
991  }
992 
993  keypoints3D = util3d::generateKeypoints3DStereo(
994  leftCorners,
995  rightCorners,
996  data.stereoCameraModels()[0],
997  status,
998  _minDepth,
999  _maxDepth);
1000  }
1001  else
1002  {
1003  int subImageWith = imageLeft.cols / data.stereoCameraModels().size();
1004  UASSERT(imageLeft.cols % subImageWith == 0);
1005  std::vector<std::vector<cv::Point2f> > subLeftCorners(data.stereoCameraModels().size());
1006  std::vector<std::vector<int> > subIndex(data.stereoCameraModels().size());
1007  // Assign keypoints per camera
1008  for(size_t i=0; i<leftCorners.size(); ++i)
1009  {
1010  int cameraIndex = int(leftCorners[i].x / subImageWith);
1011  leftCorners[i].x -= cameraIndex*subImageWith;
1012  subLeftCorners[cameraIndex].push_back(leftCorners[i]);
1013  subIndex[cameraIndex].push_back(i);
1014  }
1015 
1016  keypoints3D.resize(keypoints.size());
1017  int total = 0;
1018  int rejected = 0;
1019  for(size_t i=0; i<data.stereoCameraModels().size(); ++i)
1020  {
1021  if(!subLeftCorners[i].empty())
1022  {
1023  std::vector<unsigned char> status;
1024 #ifdef HAVE_OPENCV_CUDEV
1025  if(_stereo->isGpuEnabled())
1026  {
1027  rightCorners = _stereo->computeCorrespondences(
1028  d_imageLeft.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1029  d_imageRight.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1030  subLeftCorners[i],
1031  status);
1032  }
1033  else
1034 #endif
1035  {
1036  rightCorners = _stereo->computeCorrespondences(
1037  imageLeft.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1038  imageRight.colRange(cv::Range(subImageWith*i, subImageWith*(i+1))),
1039  subLeftCorners[i],
1040  status);
1041  }
1042 
1043  std::vector<cv::Point3f> subKeypoints3D = util3d::generateKeypoints3DStereo(
1044  subLeftCorners[i],
1045  rightCorners,
1046  data.stereoCameraModels()[i],
1047  status,
1048  _minDepth,
1049  _maxDepth);
1050 
1052  {
1053  for(size_t i=0; i<status.size(); ++i)
1054  {
1055  if(status[i]==0)
1056  {
1057  ++rejected;
1058  }
1059  }
1060  total+=status.size();
1061  }
1062 
1063  UASSERT(subIndex[i].size() == subKeypoints3D.size());
1064  for(size_t j=0; j<subKeypoints3D.size(); ++j)
1065  {
1066  keypoints3D[subIndex[i][j]] = subKeypoints3D[j];
1067  }
1068  }
1069  }
1070 
1072  {
1073  if(rejected > total/2)
1074  {
1075  UWARN("A large number (%d/%d) of stereo correspondences are rejected! "
1076  "Optical flow may have failed because images are not calibrated, "
1077  "the background is too far (no disparity between the images), "
1078  "maximum disparity may be too small (%f) or that exposure between "
1079  "left and right images is too different.",
1080  rejected,
1081  total,
1082  _stereo->maxDisparity());
1083  }
1084  }
1085  }
1086  }
1087  else if(!data.depthRaw().empty() && data.cameraModels().size())
1088  {
1089  keypoints3D = util3d::generateKeypoints3DDepth(
1090  keypoints,
1091  data.depthOrRightRaw(),
1092  data.cameraModels(),
1093  _minDepth,
1094  _maxDepth);
1095  }
1096  }
1097 
1098  return keypoints3D;
1099 }
1100 
1102 //SURF
1104 SURF::SURF(const ParametersMap & parameters) :
1105  hessianThreshold_(Parameters::defaultSURFHessianThreshold()),
1106  nOctaves_(Parameters::defaultSURFOctaves()),
1107  nOctaveLayers_(Parameters::defaultSURFOctaveLayers()),
1108  extended_(Parameters::defaultSURFExtended()),
1109  upright_(Parameters::defaultSURFUpright()),
1110  gpuKeypointsRatio_(Parameters::defaultSURFGpuKeypointsRatio()),
1111  gpuVersion_(Parameters::defaultSURFGpuVersion())
1112 {
1113  parseParameters(parameters);
1114 }
1115 
1117 {
1118 }
1119 
1120 void SURF::parseParameters(const ParametersMap & parameters)
1121 {
1122  Feature2D::parseParameters(parameters);
1123 
1124  Parameters::parse(parameters, Parameters::kSURFExtended(), extended_);
1125  Parameters::parse(parameters, Parameters::kSURFHessianThreshold(), hessianThreshold_);
1126  Parameters::parse(parameters, Parameters::kSURFOctaveLayers(), nOctaveLayers_);
1127  Parameters::parse(parameters, Parameters::kSURFOctaves(), nOctaves_);
1128  Parameters::parse(parameters, Parameters::kSURFUpright(), upright_);
1129  Parameters::parse(parameters, Parameters::kSURFGpuKeypointsRatio(), gpuKeypointsRatio_);
1130  Parameters::parse(parameters, Parameters::kSURFGpuVersion(), gpuVersion_);
1131 
1132 #ifdef RTABMAP_NONFREE
1133 #if CV_MAJOR_VERSION < 3
1134  if(gpuVersion_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1135  {
1136  UWARN("GPU version of SURF not available! Using CPU version instead...");
1137  gpuVersion_ = false;
1138  }
1139 #else
1140  if(gpuVersion_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1141  {
1142  UWARN("GPU version of SURF not available! Using CPU version instead...");
1143  gpuVersion_ = false;
1144  }
1145 #endif
1146  if(gpuVersion_)
1147  {
1149  }
1150  else
1151  {
1152 #if CV_MAJOR_VERSION < 3
1154 #else
1156 #endif
1157  }
1158 #else
1159  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1160 #endif
1161 }
1162 
1163 std::vector<cv::KeyPoint> SURF::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1164 {
1165  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1166  std::vector<cv::KeyPoint> keypoints;
1167 
1168 #ifdef RTABMAP_NONFREE
1169  cv::Mat imgRoi(image, roi);
1170  cv::Mat maskRoi;
1171  if(!mask.empty())
1172  {
1173  maskRoi = cv::Mat(mask, roi);
1174  }
1175  if(gpuVersion_)
1176  {
1177 #if CV_MAJOR_VERSION < 3
1178  cv::gpu::GpuMat imgGpu(imgRoi);
1179  cv::gpu::GpuMat maskGpu(maskRoi);
1180  (*_gpuSurf.obj)(imgGpu, maskGpu, keypoints);
1181 #else
1182  cv::cuda::GpuMat imgGpu(imgRoi);
1183  cv::cuda::GpuMat maskGpu(maskRoi);
1184  (*_gpuSurf.get())(imgGpu, maskGpu, keypoints);
1185 #endif
1186  }
1187  else
1188  {
1189  _surf->detect(imgRoi, keypoints, maskRoi);
1190  }
1191 #else
1192  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1193 #endif
1194  return keypoints;
1195 }
1196 
1197 cv::Mat SURF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1198 {
1199  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1200  cv::Mat descriptors;
1201 #ifdef RTABMAP_NONFREE
1202  if(gpuVersion_)
1203  {
1204 #if CV_MAJOR_VERSION < 3
1205  cv::gpu::GpuMat imgGpu(image);
1206  cv::gpu::GpuMat descriptorsGPU;
1207  (*_gpuSurf.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU, true);
1208 #else
1209  cv::cuda::GpuMat imgGpu(image);
1210  cv::cuda::GpuMat descriptorsGPU;
1211  (*_gpuSurf.get())(imgGpu, cv::cuda::GpuMat(), keypoints, descriptorsGPU, true);
1212 #endif
1213 
1214  // Download descriptors
1215  if (descriptorsGPU.empty())
1216  descriptors = cv::Mat();
1217  else
1218  {
1219  UASSERT(descriptorsGPU.type() == CV_32F);
1220  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1221  descriptorsGPU.download(descriptors);
1222  }
1223  }
1224  else
1225  {
1226  _surf->compute(image, keypoints, descriptors);
1227  }
1228 #else
1229  UWARN("RTAB-Map is not built with OpenCV nonfree module so SURF cannot be used!");
1230 #endif
1231 
1232  return descriptors;
1233 }
1234 
1236 //SIFT
1238 SIFT::SIFT(const ParametersMap & parameters) :
1239  nOctaveLayers_(Parameters::defaultSIFTNOctaveLayers()),
1240  contrastThreshold_(Parameters::defaultSIFTContrastThreshold()),
1241  edgeThreshold_(Parameters::defaultSIFTEdgeThreshold()),
1242  sigma_(Parameters::defaultSIFTSigma()),
1243  preciseUpscale_(Parameters::defaultSIFTPreciseUpscale()),
1244  rootSIFT_(Parameters::defaultSIFTRootSIFT()),
1245  gpu_(Parameters::defaultSIFTGpu()),
1246  guaussianThreshold_(Parameters::defaultSIFTGaussianThreshold()),
1247  upscale_(Parameters::defaultSIFTUpscale()),
1248  cudaSiftData_(0),
1249  cudaSiftMemory_(0),
1250  cudaSiftUpscaling_(upscale_)
1251 {
1252  parseParameters(parameters);
1253 }
1254 
1256 {
1257 #ifdef RTABMAP_CUDASIFT
1258  if(cudaSiftData_) {
1259  FreeSiftData(*cudaSiftData_);
1260  delete cudaSiftData_;
1261  }
1262  if(cudaSiftMemory_) {
1263  FreeSiftTempMemory(cudaSiftMemory_);
1264  }
1265 #endif
1266 }
1267 
1268 void SIFT::parseParameters(const ParametersMap & parameters)
1269 {
1270  Feature2D::parseParameters(parameters);
1271 
1272  Parameters::parse(parameters, Parameters::kSIFTContrastThreshold(), contrastThreshold_);
1273  Parameters::parse(parameters, Parameters::kSIFTEdgeThreshold(), edgeThreshold_);
1274  Parameters::parse(parameters, Parameters::kSIFTNOctaveLayers(), nOctaveLayers_);
1275  Parameters::parse(parameters, Parameters::kSIFTSigma(), sigma_);
1276  Parameters::parse(parameters, Parameters::kSIFTPreciseUpscale(), preciseUpscale_);
1277  Parameters::parse(parameters, Parameters::kSIFTRootSIFT(), rootSIFT_);
1278  Parameters::parse(parameters, Parameters::kSIFTGpu(), gpu_);
1279  Parameters::parse(parameters, Parameters::kSIFTGaussianThreshold(), guaussianThreshold_);
1280  Parameters::parse(parameters, Parameters::kSIFTUpscale(), upscale_);
1281 
1282  if(gpu_)
1283  {
1284 #ifdef RTABMAP_CUDASIFT
1285  // Check if there is a cuda device
1286  if(InitCuda(0, ULogger::level() == ULogger::kDebug)) {
1287  UDEBUG("Init SiftData");
1288  if(cudaSiftData_ == 0) {
1289  cudaSiftData_ = new SiftData();
1290  InitSiftData(*cudaSiftData_, 8192, true, true);
1291  }
1292  }
1293  else{
1294  UWARN("No cuda device(s) detected, CudaSift is not available! Using SIFT CPU version instead.");
1295  gpu_ = false;
1296  }
1297 #else
1298  UWARN("RTAB-Map is not built with CudaSift so %s cannot be used!", Parameters::kSIFTGpu().c_str());
1299  gpu_ = false;
1300 #endif
1301  }
1302 
1303  if(!gpu_)
1304  {
1305  #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)))
1306 #ifdef RTABMAP_NONFREE
1307 #if CV_MAJOR_VERSION < 3
1308  sift_ = cv::Ptr<CV_SIFT>(new CV_SIFT(this->getMaxFeatures(), nOctaveLayers_, contrastThreshold_, edgeThreshold_, sigma_));
1309 #else
1311 #endif
1312 #else
1313  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1314 #endif
1315 #elif CV_MAJOR_VERSION>4 || (CV_MAJOR_VERSION==4 && CV_MINOR_VERSION>=8)// >=4.8
1317 #else // >=4.4, >=3.4.11
1319 #endif
1320  }
1321 
1322 }
1323 
1324 std::vector<cv::KeyPoint> SIFT::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1325 {
1326  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1327  std::vector<cv::KeyPoint> keypoints;
1328  cv::Mat imgRoi(image, roi);
1329  cv::Mat maskRoi;
1330  if(!mask.empty())
1331  {
1332  maskRoi = cv::Mat(mask, roi);
1333  }
1334 #ifdef RTABMAP_CUDASIFT
1335  if(gpu_)
1336  {
1337  /* Read image using OpenCV and convert to floating point. */
1338  int w = imgRoi.cols;
1339  int h = imgRoi.rows;
1340  cv::Mat img_h;
1341  imgRoi.convertTo(img_h, CV_32FC1);
1342  CudaImage img_d;
1343  img_d.Allocate(w, h, iAlignUp(w, 128), false, NULL, (float*)img_h.data);
1344  img_d.Download();
1345 
1346  // Compute number of octaves like OpenCV based on resolution
1347  // ref: https://github.com/opencv/opencv/blob/4d665419992dda6e40364f741ae4765176b64bb0/modules/features2d/src/sift.dispatch.cpp#L538
1348  // *** stack smashing detected *** if "-2" term is higher
1349  int numOctaves = cvRound(std::log( (double)std::min(w*(upscale_?2:1), h*(upscale_?2:1)) ) / std::log(2.) - (upscale_?3:2));
1350  if(numOctaves < 1) {
1351  numOctaves = 1;
1352  }
1353  else if (numOctaves>7)
1354  {
1355  numOctaves = 7; // hard-coded limit in CudaSift
1356  }
1357  float initBlur = sigma_; /* Amount of initial Gaussian blurring in standard deviations */
1358  float thresh = guaussianThreshold_; /* Threshold on difference of Gaussians for feature pruning */
1359  float edgeLimit = edgeThreshold_;
1360  float minScale = 0.0f; /* Minimum acceptable scale to remove fine-scale features */
1361  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);
1362 
1363  if(cudaSiftMemory_ && (cudaSiftMemorySize_ != cv::Size(w, h) || cudaSiftUpscaling_ != upscale_)) {
1364  // Resolution changed, reset buffer
1365  FreeSiftTempMemory(cudaSiftMemory_);
1366  cudaSiftMemory_ = 0;
1367  }
1368 
1369  if(cudaSiftMemory_ == 0) {
1370  cudaSiftMemory_ = AllocSiftTempMemory(w, h, numOctaves, upscale_);
1371  UASSERT(cudaSiftMemory_ != 0);
1372  cudaSiftMemorySize_ = cv::Size(w, h);
1374  }
1375 
1376  ExtractSift(*cudaSiftData_, img_d, numOctaves, initBlur, thresh, edgeLimit, minScale, upscale_, cudaSiftMemory_);
1377  UDEBUG("%d features extracted", cudaSiftData_->numPts);
1378 
1379  // Convert CudaSift into OpenCV format
1380  cudaSiftDescriptors_ = cv::Mat();
1381  if(cudaSiftData_->numPts)
1382  {
1383  int maxKeypoints = this->getMaxFeatures();
1384  if(maxKeypoints == 0 || maxKeypoints > cudaSiftData_->numPts)
1385  {
1386  maxKeypoints = cudaSiftData_->numPts;
1387  }
1388 
1389  // Re-using same implementation of limitKeypoints() directly here to avoid doubling memory copies
1390  // Sort words by hessian
1391  std::multimap<float, int> hessianMap; // <hessian,id>
1392  for(int i=0; i<cudaSiftData_->numPts; ++i)
1393  {
1394  // Ignore keypoints with invalid descriptors
1395  float *desc = cudaSiftData_->h_data[i].data;
1396  if(desc[0] != 0 && desc[0] == desc[63] && desc[0] == desc[127])
1397  {
1398  //UWARN("Invalid decsriptor? skipping: %f,%f,%f", cudaSiftData_->h_data[i].xpos, cudaSiftData_->h_data[i].ypos, cudaSiftData_->h_data[i].scale);
1399  //std::cout << cv::Mat(1, 128*4, CV_8UC1, desc) << std::endl;
1400  continue;
1401  }
1402  // Ignore keypoints not in the mask
1403  if(!maskRoi.empty() && maskRoi.at<unsigned char>(cudaSiftData_->h_data[i].ypos, cudaSiftData_->h_data[i].xpos) == 0)
1404  {
1405  continue;
1406  }
1407 
1408  //Keep track of the data, to be easier to manage the data in the next step
1409  hessianMap.insert(std::pair<float, int>(cudaSiftData_->h_data[i].sharpness, i));
1410  }
1411 
1412  if((int)hessianMap.size() < maxKeypoints)
1413  {
1414  maxKeypoints = hessianMap.size();
1415  }
1416 
1417  std::multimap<float, int>::reverse_iterator iter = hessianMap.rbegin();
1418  keypoints.resize(maxKeypoints);
1419  cudaSiftDescriptors_ = cv::Mat(maxKeypoints, 128, CV_32FC1);
1420  for(unsigned int k=0; k<keypoints.size() && iter!=hessianMap.rend(); ++k, ++iter)
1421  {
1422  int i = iter->second;
1423  float *desc = cudaSiftData_->h_data[i].data;
1424  cv::Mat(1, 128, CV_32FC1, desc).copyTo(cudaSiftDescriptors_.row(k));
1425  keypoints[k].pt.x = cudaSiftData_->h_data[i].xpos;
1426  keypoints[k].pt.y = cudaSiftData_->h_data[i].ypos;
1427  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
1428  keypoints[k].angle = cudaSiftData_->h_data[i].orientation;
1429  keypoints[k].response = cudaSiftData_->h_data[i].sharpness;
1430  keypoints[k].octave = log2(cudaSiftData_->h_data[i].subsampling)-(upscale_?1:0);
1431  }
1432  }
1433  }
1434  else
1435 #endif
1436  {
1437 #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)))
1438 #ifdef RTABMAP_NONFREE
1439  sift_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1440 #else
1441  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1442 #endif
1443 #else // >=4.4, >=3.4.11
1444  sift_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1445 #endif
1446  }
1447  return keypoints;
1448 }
1449 
1450 cv::Mat SIFT::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1451 {
1452 #ifdef RTABMAP_CUDASIFT
1453  if(gpu_)
1454  {
1455  if((int)keypoints.size() == cudaSiftDescriptors_.rows)
1456  {
1457  return cudaSiftDescriptors_.clone();
1458  }
1459  else
1460  {
1461  UERROR("CudaSift: keypoints size %ld is not equal to extracted descriptors size %d", keypoints.size(), cudaSiftDescriptors_.rows);
1462  return cv::Mat();
1463  }
1464  }
1465 #endif
1466 
1467  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1468  cv::Mat descriptors;
1469 #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)))
1470 #ifdef RTABMAP_NONFREE
1471  sift_->compute(image, keypoints, descriptors);
1472 #else
1473  UWARN("RTAB-Map is not built with OpenCV nonfree module so SIFT cannot be used!");
1474 #endif
1475 #else // >=4.4, >=3.4.11
1476  sift_->compute(image, keypoints, descriptors);
1477 #endif
1478  if( rootSIFT_ && !descriptors.empty())
1479  {
1480  UDEBUG("Performing RootSIFT...");
1481  // see http://www.pyimagesearch.com/2015/04/13/implementing-rootsift-in-python-and-opencv/
1482  // apply the Hellinger kernel by first L1-normalizing and taking the
1483  // square-root
1484  for(int i=0; i<descriptors.rows; ++i)
1485  {
1486  // By taking the L1 norm, followed by the square-root, we have
1487  // already L2 normalized the feature vector and further normalization
1488  // is not needed.
1489  descriptors.row(i) = descriptors.row(i) / cv::sum(descriptors.row(i))[0];
1490  cv::sqrt(descriptors.row(i), descriptors.row(i));
1491  }
1492  }
1493  return descriptors;
1494 }
1495 
1497 //ORB
1499 ORB::ORB(const ParametersMap & parameters) :
1500  scaleFactor_(Parameters::defaultORBScaleFactor()),
1501  nLevels_(Parameters::defaultORBNLevels()),
1502  edgeThreshold_(Parameters::defaultORBEdgeThreshold()),
1503  firstLevel_(Parameters::defaultORBFirstLevel()),
1504  WTA_K_(Parameters::defaultORBWTA_K()),
1505  scoreType_(Parameters::defaultORBScoreType()),
1506  patchSize_(Parameters::defaultORBPatchSize()),
1507  gpu_(Parameters::defaultORBGpu()),
1508  fastThreshold_(Parameters::defaultFASTThreshold()),
1509  nonmaxSuppresion_(Parameters::defaultFASTNonmaxSuppression())
1510 {
1511  parseParameters(parameters);
1512 }
1513 
1515 {
1516 }
1517 
1518 void ORB::parseParameters(const ParametersMap & parameters)
1519 {
1520  Feature2D::parseParameters(parameters);
1521 
1522  Parameters::parse(parameters, Parameters::kORBScaleFactor(), scaleFactor_);
1523  Parameters::parse(parameters, Parameters::kORBNLevels(), nLevels_);
1524  Parameters::parse(parameters, Parameters::kORBEdgeThreshold(), edgeThreshold_);
1525  Parameters::parse(parameters, Parameters::kORBFirstLevel(), firstLevel_);
1526  Parameters::parse(parameters, Parameters::kORBWTA_K(), WTA_K_);
1527  Parameters::parse(parameters, Parameters::kORBScoreType(), scoreType_);
1528  Parameters::parse(parameters, Parameters::kORBPatchSize(), patchSize_);
1529  Parameters::parse(parameters, Parameters::kORBGpu(), gpu_);
1530 
1531  Parameters::parse(parameters, Parameters::kFASTThreshold(), fastThreshold_);
1532  Parameters::parse(parameters, Parameters::kFASTNonmaxSuppression(), nonmaxSuppresion_);
1533 
1534 #if CV_MAJOR_VERSION < 3
1535 #ifdef HAVE_OPENCV_GPU
1536  if(gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1537  {
1538  UWARN("GPU version of ORB not available! Using CPU version instead...");
1539  gpu_ = false;
1540  }
1541 #else
1542  if(gpu_)
1543  {
1544  UWARN("GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1545  gpu_ = false;
1546  }
1547 #endif
1548 #else
1549 #ifndef HAVE_OPENCV_CUDAFEATURES2D
1550  if(gpu_)
1551  {
1552  UWARN("GPU version of ORB not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1553  gpu_ = false;
1554  }
1555 #endif
1556  if(gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1557  {
1558  UWARN("GPU version of ORB not available (no GPU found)! Using CPU version instead...");
1559  gpu_ = false;
1560  }
1561 #endif
1562  if(gpu_)
1563  {
1564 #if CV_MAJOR_VERSION < 3
1565 #ifdef HAVE_OPENCV_GPU
1567  _gpuOrb->setFastParams(fastThreshold_, nonmaxSuppresion_);
1568 #else
1569  UFATAL("not supposed to be here");
1570 #endif
1571 #else
1572 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1574 #endif
1575 #endif
1576  }
1577  else
1578  {
1579 #if CV_MAJOR_VERSION < 3
1580  _orb = cv::Ptr<CV_ORB>(new CV_ORB(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, scoreType_, patchSize_, parameters));
1581 #elif CV_MAJOR_VERSION > 3
1582  _orb = CV_ORB::create(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, (cv::ORB::ScoreType)scoreType_, patchSize_, fastThreshold_);
1583 #else
1584  _orb = CV_ORB::create(this->getMaxFeatures(), scaleFactor_, nLevels_, edgeThreshold_, firstLevel_, WTA_K_, scoreType_, patchSize_, fastThreshold_);
1585 #endif
1586  }
1587 }
1588 
1589 std::vector<cv::KeyPoint> ORB::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1590 {
1591  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1592  std::vector<cv::KeyPoint> keypoints;
1593  cv::Mat imgRoi(image, roi);
1594  cv::Mat maskRoi;
1595  if(!mask.empty())
1596  {
1597  maskRoi = cv::Mat(mask, roi);
1598  }
1599 
1600  if(gpu_)
1601  {
1602 #if CV_MAJOR_VERSION < 3
1603 #ifdef HAVE_OPENCV_GPU
1604  cv::gpu::GpuMat imgGpu(imgRoi);
1605  cv::gpu::GpuMat maskGpu(maskRoi);
1606  (*_gpuOrb.obj)(imgGpu, maskGpu, keypoints);
1607 #else
1608  UERROR("Cannot use ORBGPU because OpenCV is not built with gpu module.");
1609 #endif
1610 #else
1611 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1612  cv::cuda::GpuMat d_image(imgRoi);
1613  cv::cuda::GpuMat d_mask(maskRoi);
1614  try {
1615  _gpuOrb->detectAndCompute(d_image, d_mask, keypoints, cv::cuda::GpuMat(), false);
1616  } catch (cv::Exception& e) {
1617  const char* err_msg = e.what();
1618  UWARN("OpenCV exception caught: %s", err_msg);
1619  }
1620 #endif
1621 #endif
1622  }
1623  else
1624  {
1625  _orb->detect(imgRoi, keypoints, maskRoi);
1626  }
1627 
1628  return keypoints;
1629 }
1630 
1631 cv::Mat ORB::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1632 {
1633  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1634  cv::Mat descriptors;
1635  if(image.empty())
1636  {
1637  ULOGGER_ERROR("Image is null ?!?");
1638  return descriptors;
1639  }
1640  if(gpu_)
1641  {
1642 #if CV_MAJOR_VERSION < 3
1643 #ifdef HAVE_OPENCV_GPU
1644  cv::gpu::GpuMat imgGpu(image);
1645  cv::gpu::GpuMat descriptorsGPU;
1646  (*_gpuOrb.obj)(imgGpu, cv::gpu::GpuMat(), keypoints, descriptorsGPU);
1647  // Download descriptors
1648  if (descriptorsGPU.empty())
1649  descriptors = cv::Mat();
1650  else
1651  {
1652  UASSERT(descriptorsGPU.type() == CV_32F);
1653  descriptors = cv::Mat(descriptorsGPU.size(), CV_32F);
1654  descriptorsGPU.download(descriptors);
1655  }
1656 #else
1657  UERROR("GPU version of ORB not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1658 #endif
1659 #else
1660 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1661  cv::cuda::GpuMat d_image(image);
1662  cv::cuda::GpuMat d_descriptors;
1663  try {
1664  _gpuOrb->detectAndCompute(d_image, cv::cuda::GpuMat(), keypoints, d_descriptors, true);
1665  } catch (cv::Exception& e) {
1666  const char* err_msg = e.what();
1667  UWARN("OpenCV exception caught: %s", err_msg);
1668  }
1669  // Download descriptors
1670  if (d_descriptors.empty())
1671  descriptors = cv::Mat();
1672  else
1673  {
1674  UASSERT(d_descriptors.type() == CV_32F || d_descriptors.type() == CV_8U);
1675  d_descriptors.download(descriptors);
1676  }
1677 #endif
1678 #endif
1679  }
1680  else
1681  {
1682  _orb->compute(image, keypoints, descriptors);
1683  }
1684 
1685  return descriptors;
1686 }
1687 
1689 //FAST
1691 FAST::FAST(const ParametersMap & parameters) :
1692  threshold_(Parameters::defaultFASTThreshold()),
1693  nonmaxSuppression_(Parameters::defaultFASTNonmaxSuppression()),
1694  gpu_(Parameters::defaultFASTGpu()),
1695  gpuKeypointsRatio_(Parameters::defaultFASTGpuKeypointsRatio()),
1696  minThreshold_(Parameters::defaultFASTMinThreshold()),
1697  maxThreshold_(Parameters::defaultFASTMaxThreshold()),
1698  gridRows_(Parameters::defaultFASTGridRows()),
1699  gridCols_(Parameters::defaultFASTGridCols()),
1700  fastCV_(Parameters::defaultFASTCV()),
1701  fastCVinit_(false),
1702  fastCVMaxFeatures_(10000),
1703  fastCVLastImageHeight_(0)
1704 {
1705 #ifdef RTABMAP_FASTCV
1706  char sVersion[128] = { 0 };
1707  fcvGetVersion(sVersion, 128);
1708  UINFO("fastcv version = %s", sVersion);
1709  int ix;
1710  if ((ix = fcvSetOperationMode(FASTCV_OP_PERFORMANCE)))
1711  {
1712  UERROR("fcvSetOperationMode return=%d, OpenCV FAST will be used instead!", ix);
1713  fastCV_ = 0;
1714  }
1715  else
1716  {
1717  fcvMemInit();
1718 
1719  if (!(fastCVCorners_ = (uint32_t*)fcvMemAlloc(fastCVMaxFeatures_ * sizeof(uint32_t) * 2, 16)) ||
1720  !(fastCVCornerScores_ = (uint32_t*)fcvMemAlloc( fastCVMaxFeatures_ * sizeof(uint32_t), 16 )))
1721  {
1722  UERROR("could not alloc fastcv mem, using opencv fast instead!");
1723 
1724  if (fastCVCorners_)
1725  {
1726  fcvMemFree(fastCVCorners_);
1727  fastCVCorners_ = NULL;
1728  }
1729  if (fastCVCornerScores_)
1730  {
1731  fcvMemFree(fastCVCornerScores_);
1733  }
1734  }
1735  else
1736  {
1737  fastCVinit_ = true;
1738  }
1739  }
1740  #endif
1741  parseParameters(parameters);
1742 }
1743 
1745 {
1746 #ifdef RTABMAP_FASTCV
1747  if(fastCVinit_)
1748  {
1749  fcvMemDeInit();
1750 
1751  if (fastCVCorners_)
1752  fcvMemFree(fastCVCorners_);
1753  if (fastCVCornerScores_)
1754  fcvMemFree(fastCVCornerScores_);
1755  if (fastCVTempBuf_)
1756  fcvMemFree(fastCVTempBuf_);
1757  }
1758 #endif
1759 }
1760 
1761 void FAST::parseParameters(const ParametersMap & parameters)
1762 {
1763  Feature2D::parseParameters(parameters);
1764 
1765  Parameters::parse(parameters, Parameters::kFASTThreshold(), threshold_);
1766  Parameters::parse(parameters, Parameters::kFASTNonmaxSuppression(), nonmaxSuppression_);
1767  Parameters::parse(parameters, Parameters::kFASTGpu(), gpu_);
1768  Parameters::parse(parameters, Parameters::kFASTGpuKeypointsRatio(), gpuKeypointsRatio_);
1769 
1770  Parameters::parse(parameters, Parameters::kFASTMinThreshold(), minThreshold_);
1771  Parameters::parse(parameters, Parameters::kFASTMaxThreshold(), maxThreshold_);
1772  Parameters::parse(parameters, Parameters::kFASTGridRows(), gridRows_);
1773  Parameters::parse(parameters, Parameters::kFASTGridCols(), gridCols_);
1774 
1775  Parameters::parse(parameters, Parameters::kFASTCV(), fastCV_);
1776  UASSERT(fastCV_ == 0 || fastCV_ == 9 || fastCV_ == 10);
1777 
1780 
1781 #if CV_MAJOR_VERSION < 3
1782 #ifdef HAVE_OPENCV_GPU
1783  if(gpu_ && cv::gpu::getCudaEnabledDeviceCount() == 0)
1784  {
1785  UWARN("GPU version of FAST not available! Using CPU version instead...");
1786  gpu_ = false;
1787  }
1788 #else
1789  if(gpu_)
1790  {
1791  UWARN("GPU version of FAST not available (OpenCV not built with gpu/cuda module)! Using CPU version instead...");
1792  gpu_ = false;
1793  }
1794 #endif
1795 #else
1796 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1797  if(gpu_ && cv::cuda::getCudaEnabledDeviceCount() == 0)
1798  {
1799  UWARN("GPU version of FAST not available! Using CPU version instead...");
1800  gpu_ = false;
1801  }
1802 #else
1803  if(gpu_)
1804  {
1805  UWARN("GPU version of FAST not available (OpenCV cudafeatures2d module)! Using CPU version instead...");
1806  gpu_ = false;
1807  }
1808 #endif
1809 #endif
1810  if(gpu_)
1811  {
1812 #if CV_MAJOR_VERSION < 3
1813 #ifdef HAVE_OPENCV_GPU
1815 #else
1816  UFATAL("not supposed to be here!");
1817 #endif
1818 #else
1819 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1820  UFATAL("not implemented");
1821 #endif
1822 #endif
1823  }
1824  else
1825  {
1826 #if CV_MAJOR_VERSION < 3
1827  if(gridRows_ > 0 && gridCols_ > 0)
1828  {
1829  UDEBUG("grid max features = %d", this->getMaxFeatures());
1830  cv::Ptr<cv::FeatureDetector> fastAdjuster = cv::Ptr<cv::FastAdjuster>(new cv::FastAdjuster(threshold_, nonmaxSuppression_, minThreshold_, maxThreshold_));
1831  _fast = cv::Ptr<cv::FeatureDetector>(new cv::GridAdaptedFeatureDetector(fastAdjuster, this->getMaxFeatures(), gridRows_, gridCols_));
1832  }
1833  else
1834  {
1835  if(gridRows_ > 0)
1836  {
1837  UWARN("Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1838  Parameters::kFASTGridRows().c_str(), gridRows_, Parameters::kFASTGridCols().c_str());
1839  }
1840  else if(gridCols_ > 0)
1841  {
1842  UWARN("Parameter \"%s\" is set (value=%d) but not \"%s\"! Grid adaptor will not be added.",
1843  Parameters::kFASTGridCols().c_str(), gridCols_, Parameters::kFASTGridRows().c_str());
1844  }
1845  _fast = cv::Ptr<cv::FeatureDetector>(new CV_FAST(threshold_, nonmaxSuppression_));
1846  }
1847 #else
1848  _fast = CV_FAST::create(threshold_, nonmaxSuppression_);
1849 #endif
1850  }
1851 }
1852 
1853 std::vector<cv::KeyPoint> FAST::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
1854 {
1855  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1856  std::vector<cv::KeyPoint> keypoints;
1857 
1858 #ifdef RTABMAP_FASTCV
1859  if(fastCV_>0)
1860  {
1861  // Note: mask not supported, it should be the inverse of the current mask used (0=where to extract)
1862  uint32_t nCorners = 0;
1863 
1865  if (nonmaxSuppression_)
1866  {
1867  if(fastCVTempBuf_==NULL || (fastCVTempBuf_!= NULL && fastCVLastImageHeight_!= image.rows))
1868  {
1869  if (fastCVTempBuf_)
1870  {
1871  fcvMemFree(fastCVTempBuf_);
1872  fastCVTempBuf_ = NULL;
1873  }
1874  if(!(fastCVTempBuf_ = (uint32_t*)fcvMemAlloc( (3*fastCVMaxFeatures_+image.rows+1)*4, 16 )))
1875  {
1876  UERROR("could not alloc fastcv mem for temp buf (%s=true)", Parameters::kFASTNonmaxSuppression().c_str());
1878  return keypoints;
1879  }
1880  fastCVLastImageHeight_ = image.rows;
1881  }
1882  }
1883 
1884  // image.data should be 128 bits aligned
1885  UDEBUG("%dx%d (step=%d) thr=%d maxFeatures=%d", image.cols, image.rows, image.step1(), threshold_, fastCVMaxFeatures_);
1886  if(fastCV_ == 10)
1887  {
1888  fcvCornerFast10Scoreu8(image.data, image.cols, image.rows, 0, threshold_, 0, fastCVCorners_, fastCVCornerScores_, fastCVMaxFeatures_, &nCorners, nonmaxSuppression_?1:0, fastCVTempBuf_);
1889  }
1890  else
1891  {
1892  fcvCornerFast9Scoreu8_v2(image.data, image.cols, image.rows, image.step1(), threshold_, 0, fastCVCorners_, fastCVCornerScores_, fastCVMaxFeatures_, &nCorners, nonmaxSuppression_?1:0, fastCVTempBuf_);
1893  }
1894  UDEBUG("number of corners found = %d:", nCorners);
1895  keypoints.resize(nCorners);
1896  for (uint32_t i = 0; i < nCorners; i++)
1897  {
1898  keypoints[i].pt.x = fastCVCorners_[i * 2];
1899  keypoints[i].pt.y = fastCVCorners_[(i * 2) + 1];
1900  keypoints[i].size = 3;
1901  keypoints[i].response = fastCVCornerScores_[i];
1902  }
1903 
1904  if(this->getMaxFeatures() > 0)
1905  {
1906  this->limitKeypoints(keypoints, this->getMaxFeatures());
1907  }
1908  return keypoints;
1909  }
1910 #endif
1911 
1912  if(fastCV_>0)
1913  {
1914  UWARN( "RTAB-Map is not built with FastCV support. OpenCV's FAST is used instead. "
1915  "Please set %s to 0. This message will only appear once.",
1916  Parameters::kFASTCV().c_str());
1917  fastCV_ = 0;
1918  }
1919 
1920  cv::Mat imgRoi(image, roi);
1921  cv::Mat maskRoi;
1922  if(!mask.empty())
1923  {
1924  maskRoi = cv::Mat(mask, roi);
1925  }
1926  if(gpu_)
1927  {
1928 #if CV_MAJOR_VERSION < 3
1929 #ifdef HAVE_OPENCV_GPU
1930  cv::gpu::GpuMat imgGpu(imgRoi);
1931  cv::gpu::GpuMat maskGpu(maskRoi);
1932  (*_gpuFast.obj)(imgGpu, maskGpu, keypoints);
1933 #else
1934  UERROR("Cannot use FAST GPU because OpenCV is not built with gpu module.");
1935 #endif
1936 #else
1937 #ifdef HAVE_OPENCV_CUDAFEATURES2D
1938  UFATAL("not implemented");
1939 #endif
1940 #endif
1941  }
1942  else
1943  {
1944  _fast->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
1945  }
1946  return keypoints;
1947 }
1948 
1950 //FAST-BRIEF
1953  FAST(parameters),
1954  bytes_(Parameters::defaultBRIEFBytes())
1955 {
1956  parseParameters(parameters);
1957 }
1958 
1960 {
1961 }
1962 
1964 {
1965  FAST::parseParameters(parameters);
1966 
1967  Parameters::parse(parameters, Parameters::kBRIEFBytes(), bytes_);
1968 #if CV_MAJOR_VERSION < 3
1969  _brief = cv::Ptr<CV_BRIEF>(new CV_BRIEF(bytes_));
1970 #else
1971 #ifdef HAVE_OPENCV_XFEATURES2D
1972  _brief = CV_BRIEF::create(bytes_);
1973 #else
1974  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1975 #endif
1976 #endif
1977 }
1978 
1979 cv::Mat FAST_BRIEF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
1980 {
1981  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
1982  cv::Mat descriptors;
1983 #if CV_MAJOR_VERSION < 3
1984  _brief->compute(image, keypoints, descriptors);
1985 #else
1986 #ifdef HAVE_OPENCV_XFEATURES2D
1987  _brief->compute(image, keypoints, descriptors);
1988 #else
1989  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
1990 #endif
1991 #endif
1992  return descriptors;
1993 }
1994 
1996 //FAST-FREAK
1999  FAST(parameters),
2000  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2001  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2002  patternScale_(Parameters::defaultFREAKPatternScale()),
2003  nOctaves_(Parameters::defaultFREAKNOctaves())
2004 {
2005  parseParameters(parameters);
2006 }
2007 
2009 {
2010 }
2011 
2013 {
2014  FAST::parseParameters(parameters);
2015 
2016  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2017  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2018  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2019  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2020 
2021 #if CV_MAJOR_VERSION < 3
2023 #else
2024 #ifdef HAVE_OPENCV_XFEATURES2D
2026 #else
2027  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2028 #endif
2029 #endif
2030 }
2031 
2032 cv::Mat FAST_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2033 {
2034  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2035  cv::Mat descriptors;
2036 #if CV_MAJOR_VERSION < 3
2037  _freak->compute(image, keypoints, descriptors);
2038 #else
2039 #ifdef HAVE_OPENCV_XFEATURES2D
2040  _freak->compute(image, keypoints, descriptors);
2041 #else
2042  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2043 #endif
2044 #endif
2045  return descriptors;
2046 }
2047 
2049 //GFTT
2051 GFTT::GFTT(const ParametersMap & parameters) :
2052  _qualityLevel(Parameters::defaultGFTTQualityLevel()),
2053  _minDistance(Parameters::defaultGFTTMinDistance()),
2054  _blockSize(Parameters::defaultGFTTBlockSize()),
2055  _useHarrisDetector(Parameters::defaultGFTTUseHarrisDetector()),
2056  _k(Parameters::defaultGFTTK()),
2057  _gpu(Parameters::defaultGFTTGpu())
2058 {
2059  parseParameters(parameters);
2060 }
2061 
2063 {
2064 }
2065 
2066 void GFTT::parseParameters(const ParametersMap & parameters)
2067 {
2068  Feature2D::parseParameters(parameters);
2069 
2070  Parameters::parse(parameters, Parameters::kGFTTQualityLevel(), _qualityLevel);
2071  Parameters::parse(parameters, Parameters::kGFTTMinDistance(), _minDistance);
2072  Parameters::parse(parameters, Parameters::kGFTTBlockSize(), _blockSize);
2073  Parameters::parse(parameters, Parameters::kGFTTUseHarrisDetector(), _useHarrisDetector);
2074  Parameters::parse(parameters, Parameters::kGFTTK(), _k);
2075  Parameters::parse(parameters, Parameters::kGFTTGpu(), _gpu);
2076 
2077 #if CV_MAJOR_VERSION < 3
2078  if(_gpu)
2079  {
2080  UWARN("GPU version of GFTT is not implemented for OpenCV<3! Using CPU version instead...");
2081  _gpu = false;
2082  }
2083 #endif
2084 
2085 #ifdef HAVE_OPENCV_CUDAIMGPROC
2086  if(_gpu && cv::cuda::getCudaEnabledDeviceCount() == 0)
2087  {
2088  UWARN("GPU version of GFTT not available! Using CPU version instead...");
2089  _gpu = false;
2090  }
2091 #else
2092  if(_gpu)
2093  {
2094  UWARN("GPU version of GFTT not available (OpenCV cudaimageproc module)! Using CPU version instead...");
2095  _gpu = false;
2096  }
2097 #endif
2098  if(_gpu)
2099  {
2100 #ifdef HAVE_OPENCV_CUDAIMGPROC
2101  _gpuGftt = cv::cuda::createGoodFeaturesToTrackDetector(CV_8UC1, this->getMaxFeatures(), _qualityLevel, _minDistance, _blockSize, _useHarrisDetector ,_k);
2102 #else
2103  UFATAL("not supposed to be here!");
2104 #endif
2105  }
2106  else
2107  {
2108 #if CV_MAJOR_VERSION < 3
2109  _gftt = cv::Ptr<CV_GFTT>(new CV_GFTT(this->getMaxFeatures(), _qualityLevel, _minDistance, _blockSize, _useHarrisDetector ,_k));
2110 #else
2112 #endif
2113  }
2114 }
2115 
2116 std::vector<cv::KeyPoint> GFTT::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2117 {
2118  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2119  std::vector<cv::KeyPoint> keypoints;
2120  cv::Mat imgRoi(image, roi);
2121  cv::Mat maskRoi;
2122  if(!mask.empty())
2123  {
2124  maskRoi = cv::Mat(mask, roi);
2125  }
2126 
2127 #if CV_MAJOR_VERSION >= 3 && defined(HAVE_OPENCV_CUDAIMGPROC)
2128  if(_gpu)
2129  {
2130  cv::cuda::GpuMat imgGpu(imgRoi);
2131  cv::cuda::GpuMat maskGpu(maskRoi);
2132  cv::cuda::GpuMat cornersGpu;
2133  _gpuGftt->detect(imgGpu, cornersGpu, maskGpu);
2134  std::vector<cv::Point2f> corners(cornersGpu.cols);
2135  cv::Mat cornersMat(1, cornersGpu.cols, CV_32FC2, (void*)&corners[0]);
2136  cornersGpu.download(cornersMat);
2137  cv::KeyPoint::convert(corners, keypoints, _blockSize);
2138  }
2139  else
2140 #endif
2141  {
2142  _gftt->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
2143  }
2144 
2145  return keypoints;
2146 }
2147 
2149 //FAST-BRIEF
2152  GFTT(parameters),
2153  bytes_(Parameters::defaultBRIEFBytes())
2154 {
2155  parseParameters(parameters);
2156 }
2157 
2159 {
2160 }
2161 
2163 {
2164  GFTT::parseParameters(parameters);
2165 
2166  Parameters::parse(parameters, Parameters::kBRIEFBytes(), bytes_);
2167 #if CV_MAJOR_VERSION < 3
2168  _brief = cv::Ptr<CV_BRIEF>(new CV_BRIEF(bytes_));
2169 #else
2170 #ifdef HAVE_OPENCV_XFEATURES2D
2171  _brief = CV_BRIEF::create(bytes_);
2172 #else
2173  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
2174 #endif
2175 #endif
2176 }
2177 
2178 cv::Mat GFTT_BRIEF::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2179 {
2180  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2181  cv::Mat descriptors;
2182 #if CV_MAJOR_VERSION < 3
2183  _brief->compute(image, keypoints, descriptors);
2184 #else
2185 #ifdef HAVE_OPENCV_XFEATURES2D
2186  _brief->compute(image, keypoints, descriptors);
2187 #else
2188  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Brief cannot be used!");
2189 #endif
2190 #endif
2191  return descriptors;
2192 }
2193 
2195 //GFTT-FREAK
2198  GFTT(parameters),
2199  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2200  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2201  patternScale_(Parameters::defaultFREAKPatternScale()),
2202  nOctaves_(Parameters::defaultFREAKNOctaves())
2203 {
2204  parseParameters(parameters);
2205 }
2206 
2208 {
2209 }
2210 
2212 {
2213  GFTT::parseParameters(parameters);
2214 
2215  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2216  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2217  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2218  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2219 
2220 #if CV_MAJOR_VERSION < 3
2222 #else
2223 #ifdef HAVE_OPENCV_XFEATURES2D
2225 #else
2226  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2227 #endif
2228 #endif
2229 }
2230 
2231 cv::Mat GFTT_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2232 {
2233  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2234  cv::Mat descriptors;
2235 #if CV_MAJOR_VERSION < 3
2236  _freak->compute(image, keypoints, descriptors);
2237 #else
2238 #ifdef HAVE_OPENCV_XFEATURES2D
2239  _freak->compute(image, keypoints, descriptors);
2240 #else
2241  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2242 #endif
2243 #endif
2244  return descriptors;
2245 }
2246 
2248 //SURF-FREAK
2251  SURF(parameters),
2252  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2253  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2254  patternScale_(Parameters::defaultFREAKPatternScale()),
2255  nOctaves_(Parameters::defaultFREAKNOctaves())
2256 {
2257  parseParameters(parameters);
2258 }
2259 
2261 {
2262 }
2263 
2265 {
2266  SURF::parseParameters(parameters);
2267 
2268  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2269  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2270  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2271  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2272 
2273 #if CV_MAJOR_VERSION < 3
2275 #else
2276 #ifdef HAVE_OPENCV_XFEATURES2D
2278 #else
2279  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2280 #endif
2281 #endif
2282 }
2283 
2284 cv::Mat SURF_FREAK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2285 {
2286  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2287  cv::Mat descriptors;
2288 #if CV_MAJOR_VERSION < 3
2289  _freak->compute(image, keypoints, descriptors);
2290 #else
2291 #ifdef HAVE_OPENCV_XFEATURES2D
2292  _freak->compute(image, keypoints, descriptors);
2293 #else
2294  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so Freak cannot be used!");
2295 #endif
2296 #endif
2297  return descriptors;
2298 }
2299 
2301 //GFTT-ORB
2303 GFTT_ORB::GFTT_ORB(const ParametersMap & parameters) :
2304  GFTT(parameters),
2305  _orb(parameters)
2306 {
2307  parseParameters(parameters);
2308 }
2309 
2311 {
2312 }
2313 
2315 {
2316  GFTT::parseParameters(parameters);
2317  _orb.parseParameters(parameters);
2318 }
2319 
2320 cv::Mat GFTT_ORB::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2321 {
2322  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2323  return _orb.generateDescriptors(image, keypoints);
2324 }
2325 
2327 //BRISK
2329 BRISK::BRISK(const ParametersMap & parameters) :
2330  thresh_(Parameters::defaultBRISKThresh()),
2331  octaves_(Parameters::defaultBRISKOctaves()),
2332  patternScale_(Parameters::defaultBRISKPatternScale())
2333 {
2334  parseParameters(parameters);
2335 }
2336 
2338 {
2339 }
2340 
2341 void BRISK::parseParameters(const ParametersMap & parameters)
2342 {
2343  Feature2D::parseParameters(parameters);
2344 
2345  Parameters::parse(parameters, Parameters::kBRISKThresh(), thresh_);
2346  Parameters::parse(parameters, Parameters::kBRISKOctaves(), octaves_);
2347  Parameters::parse(parameters, Parameters::kBRISKPatternScale(), patternScale_);
2348 
2349 #if CV_MAJOR_VERSION < 3
2350  brisk_ = cv::Ptr<CV_BRISK>(new CV_BRISK(thresh_, octaves_, patternScale_));
2351 #else
2352  brisk_ = CV_BRISK::create(thresh_, octaves_, patternScale_);
2353 #endif
2354 }
2355 
2356 std::vector<cv::KeyPoint> BRISK::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2357 {
2358  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2359  std::vector<cv::KeyPoint> keypoints;
2360  cv::Mat imgRoi(image, roi);
2361  cv::Mat maskRoi;
2362  if(!mask.empty())
2363  {
2364  maskRoi = cv::Mat(mask, roi);
2365  }
2366  brisk_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
2367  return keypoints;
2368 }
2369 
2370 cv::Mat BRISK::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2371 {
2372  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2373  cv::Mat descriptors;
2374  brisk_->compute(image, keypoints, descriptors);
2375  return descriptors;
2376 }
2377 
2379 //KAZE
2381 KAZE::KAZE(const ParametersMap & parameters) :
2382  extended_(Parameters::defaultKAZEExtended()),
2383  upright_(Parameters::defaultKAZEUpright()),
2384  threshold_(Parameters::defaultKAZEThreshold()),
2385  nOctaves_(Parameters::defaultKAZENOctaves()),
2386  nOctaveLayers_(Parameters::defaultKAZENOctaveLayers()),
2387  diffusivity_(Parameters::defaultKAZEDiffusivity())
2388 {
2389  parseParameters(parameters);
2390 }
2391 
2393 {
2394 }
2395 
2396 void KAZE::parseParameters(const ParametersMap & parameters)
2397 {
2398  Feature2D::parseParameters(parameters);
2399 
2400  Parameters::parse(parameters, Parameters::kKAZEExtended(), extended_);
2401  Parameters::parse(parameters, Parameters::kKAZEUpright(), upright_);
2402  Parameters::parse(parameters, Parameters::kKAZEThreshold(), threshold_);
2403  Parameters::parse(parameters, Parameters::kKAZENOctaves(), nOctaves_);
2404  Parameters::parse(parameters, Parameters::kKAZENOctaveLayers(), nOctaveLayers_);
2405  Parameters::parse(parameters, Parameters::kKAZEDiffusivity(), diffusivity_);
2406 
2407 #if CV_MAJOR_VERSION > 3
2408  kaze_ = cv::KAZE::create(extended_, upright_, threshold_, nOctaves_, nOctaveLayers_, (cv::KAZE::DiffusivityType)diffusivity_);
2409 #elif CV_MAJOR_VERSION > 2
2410  kaze_ = cv::KAZE::create(extended_, upright_, threshold_, nOctaves_, nOctaveLayers_, diffusivity_);
2411 #else
2412  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2413 #endif
2414 }
2415 
2416 std::vector<cv::KeyPoint> KAZE::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2417 {
2418  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2419  std::vector<cv::KeyPoint> keypoints;
2420 #if CV_MAJOR_VERSION > 2
2421  cv::Mat imgRoi(image, roi);
2422  cv::Mat maskRoi;
2423  if (!mask.empty())
2424  {
2425  maskRoi = cv::Mat(mask, roi);
2426  }
2427  kaze_->detect(imgRoi, keypoints, maskRoi); // Opencv keypoints
2428 #else
2429  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2430 #endif
2431  return keypoints;
2432 }
2433 
2434 cv::Mat KAZE::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2435 {
2436  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2437  cv::Mat descriptors;
2438 #if CV_MAJOR_VERSION > 2
2439  kaze_->compute(image, keypoints, descriptors);
2440 #else
2441  UWARN("RTAB-Map is not built with OpenCV3 so Kaze feature cannot be used!");
2442 #endif
2443  return descriptors;
2444 }
2445 
2447 //ORBOctree
2450  scaleFactor_(Parameters::defaultORBScaleFactor()),
2451  nLevels_(Parameters::defaultORBNLevels()),
2452  patchSize_(Parameters::defaultORBPatchSize()),
2453  edgeThreshold_(Parameters::defaultORBEdgeThreshold()),
2454  fastThreshold_(Parameters::defaultFASTThreshold()),
2455  fastMinThreshold_(Parameters::defaultFASTMinThreshold())
2456 {
2457  parseParameters(parameters);
2458 }
2459 
2461 {
2462 }
2463 
2465 {
2466  Feature2D::parseParameters(parameters);
2467 
2468  Parameters::parse(parameters, Parameters::kORBScaleFactor(), scaleFactor_);
2469  Parameters::parse(parameters, Parameters::kORBNLevels(), nLevels_);
2470  Parameters::parse(parameters, Parameters::kORBPatchSize(), patchSize_);
2471  Parameters::parse(parameters, Parameters::kORBEdgeThreshold(), edgeThreshold_);
2472 
2473  Parameters::parse(parameters, Parameters::kFASTThreshold(), fastThreshold_);
2474  Parameters::parse(parameters, Parameters::kFASTMinThreshold(), fastMinThreshold_);
2475 
2476 #ifdef RTABMAP_ORB_OCTREE
2478 #else
2479  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2480 #endif
2481 }
2482 
2483 std::vector<cv::KeyPoint> ORBOctree::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2484 {
2485  std::vector<cv::KeyPoint> keypoints;
2486  descriptors_ = cv::Mat();
2487 #ifdef RTABMAP_ORB_OCTREE
2488  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2489  cv::Mat imgRoi(image, roi);
2490  cv::Mat maskRoi;
2491  if(!mask.empty())
2492  {
2493  maskRoi = cv::Mat(mask, roi);
2494  }
2495 
2496  (*_orb)(imgRoi, maskRoi, keypoints, descriptors_);
2497 
2498  // OrbOctree ignores the mask, so we have to apply it manually here
2499  if(!keypoints.empty() && !maskRoi.empty())
2500  {
2501  std::vector<cv::KeyPoint> validKeypoints;
2502  validKeypoints.reserve(keypoints.size());
2503  cv::Mat validDescriptors;
2504  for(size_t i=0; i<keypoints.size(); ++i)
2505  {
2506  if(maskRoi.at<unsigned char>(keypoints[i].pt.y+roi.y, keypoints[i].pt.x+roi.x) != 0)
2507  {
2508  validKeypoints.push_back(keypoints[i]);
2509  validDescriptors.push_back(descriptors_.row(i));
2510  }
2511  }
2512  keypoints = validKeypoints;
2513  descriptors_ = validDescriptors;
2514  }
2515 
2516  if((int)keypoints.size() > this->getMaxFeatures())
2517  {
2518  limitKeypoints(keypoints, descriptors_, this->getMaxFeatures(), roi.size(), this->getSSC());
2519  }
2520 #else
2521  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2522 #endif
2523  return keypoints;
2524 }
2525 
2526 cv::Mat ORBOctree::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2527 {
2528 #ifdef RTABMAP_ORB_OCTREE
2529  UASSERT_MSG((int)keypoints.size() == descriptors_.rows, uFormat("keypoints=%d descriptors=%d", (int)keypoints.size(), descriptors_.rows).c_str());
2530 #else
2531  UWARN("RTAB-Map is not built with ORB OcTree option enabled so ORB OcTree feature cannot be used!");
2532 #endif
2533  return descriptors_;
2534 }
2535 
2537 //SuperPointTorch
2540  path_(Parameters::defaultSuperPointModelPath()),
2541  threshold_(Parameters::defaultSuperPointThreshold()),
2542  nms_(Parameters::defaultSuperPointNMS()),
2543  minDistance_(Parameters::defaultSuperPointNMSRadius()),
2544  cuda_(Parameters::defaultSuperPointCuda())
2545 {
2546  parseParameters(parameters);
2547 }
2548 
2550 {
2551 }
2552 
2554 {
2555  Feature2D::parseParameters(parameters);
2556 
2557  std::string previousPath = path_;
2558 #ifdef RTABMAP_TORCH
2559  bool previousCuda = cuda_;
2560 #endif
2561  Parameters::parse(parameters, Parameters::kSuperPointModelPath(), path_);
2562  Parameters::parse(parameters, Parameters::kSuperPointThreshold(), threshold_);
2563  Parameters::parse(parameters, Parameters::kSuperPointNMS(), nms_);
2564  Parameters::parse(parameters, Parameters::kSuperPointNMSRadius(), minDistance_);
2565  Parameters::parse(parameters, Parameters::kSuperPointCuda(), cuda_);
2566 
2567 #ifdef RTABMAP_TORCH
2568  if(superPoint_.get() == 0 || path_.compare(previousPath) != 0 || previousCuda != cuda_)
2569  {
2570  superPoint_ = cv::Ptr<SPDetector>(new SPDetector(path_, threshold_, nms_, minDistance_, cuda_));
2571  }
2572  else
2573  {
2574  superPoint_->setThreshold(threshold_);
2575  superPoint_->SetNMS(nms_);
2576  superPoint_->setMinDistance(minDistance_);
2577  }
2578 #else
2579  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2580 #endif
2581 }
2582 
2583 std::vector<cv::KeyPoint> SuperPointTorch::generateKeypointsImpl(const cv::Mat & image, const cv::Rect & roi, const cv::Mat & mask)
2584 {
2585 #ifdef RTABMAP_TORCH
2586  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2587  if(roi.x!=0 || roi.y !=0)
2588  {
2589  UERROR("SuperPoint: Not supporting ROI (%d,%d,%d,%d). Make sure %s, %s, %s, %s, %s, %s are all set to default values.",
2590  roi.x, roi.y, roi.width, roi.height,
2591  Parameters::kKpRoiRatios().c_str(),
2592  Parameters::kVisRoiRatios().c_str(),
2593  Parameters::kVisGridRows().c_str(),
2594  Parameters::kVisGridCols().c_str(),
2595  Parameters::kKpGridRows().c_str(),
2596  Parameters::kKpGridCols().c_str());
2597  return std::vector<cv::KeyPoint>();
2598  }
2599  return superPoint_->detect(image, mask);
2600 #else
2601  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2602  return std::vector<cv::KeyPoint>();
2603 #endif
2604 }
2605 
2606 cv::Mat SuperPointTorch::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2607 {
2608 #ifdef RTABMAP_TORCH
2609  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2610  return superPoint_->compute(keypoints);
2611 #else
2612  UWARN("RTAB-Map is not built with Torch support so SuperPoint Torch feature cannot be used!");
2613  return cv::Mat();
2614 #endif
2615 }
2616 
2617 
2619 //GFTT-DAISY
2622  GFTT(parameters),
2623  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2624  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2625  patternScale_(Parameters::defaultFREAKPatternScale()),
2626  nOctaves_(Parameters::defaultFREAKNOctaves())
2627 {
2628  parseParameters(parameters);
2629 }
2630 
2632 {
2633 }
2634 
2636 {
2637  GFTT::parseParameters(parameters);
2638 
2639  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2640  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2641  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2642  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2643 
2644 #ifdef HAVE_OPENCV_XFEATURES2D
2645  _daisy = CV_DAISY::create();
2646 #else
2647  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2648 #endif
2649 }
2650 
2651 cv::Mat GFTT_DAISY::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2652 {
2653  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2654  cv::Mat descriptors;
2655 #ifdef HAVE_OPENCV_XFEATURES2D
2656  _daisy->compute(image, keypoints, descriptors);
2657 #else
2658  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2659 #endif
2660  return descriptors;
2661 }
2662 
2664 //SURF-DAISY
2667  SURF(parameters),
2668  orientationNormalized_(Parameters::defaultFREAKOrientationNormalized()),
2669  scaleNormalized_(Parameters::defaultFREAKScaleNormalized()),
2670  patternScale_(Parameters::defaultFREAKPatternScale()),
2671  nOctaves_(Parameters::defaultFREAKNOctaves())
2672 {
2673  parseParameters(parameters);
2674 }
2675 
2677 {
2678 }
2679 
2681 {
2682  SURF::parseParameters(parameters);
2683 
2684  Parameters::parse(parameters, Parameters::kFREAKOrientationNormalized(), orientationNormalized_);
2685  Parameters::parse(parameters, Parameters::kFREAKScaleNormalized(), scaleNormalized_);
2686  Parameters::parse(parameters, Parameters::kFREAKPatternScale(), patternScale_);
2687  Parameters::parse(parameters, Parameters::kFREAKNOctaves(), nOctaves_);
2688 
2689 #ifdef HAVE_OPENCV_XFEATURES2D
2690  _daisy = CV_DAISY::create();
2691 #else
2692  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2693 #endif
2694 }
2695 
2696 cv::Mat SURF_DAISY::generateDescriptorsImpl(const cv::Mat & image, std::vector<cv::KeyPoint> & keypoints) const
2697 {
2698  UASSERT(!image.empty() && image.channels() == 1 && image.depth() == CV_8U);
2699  cv::Mat descriptors;
2700 #ifdef HAVE_OPENCV_XFEATURES2D
2701  _daisy->compute(image, keypoints, descriptors);
2702 #else
2703  UWARN("RTAB-Map is not built with OpenCV xfeatures2d module so DAISY cannot be used!");
2704 #endif
2705  return descriptors;
2706 }
2707 
2708 }
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:1631
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:1163
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:2116
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:2320
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:2464
rtabmap::Feature2D::kFeaturePyDetector
@ kFeaturePyDetector
Definition: Features2d.h:132
rtabmap::FAST::~FAST
virtual ~FAST()
Definition: Features2d.cpp:1744
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:2250
rtabmap::ORBOctree
Definition: Features2d.h:581
rtabmap::GFTT_ORB::_orb
ORB _orb
Definition: Features2d.h:528
rtabmap::BRISK::~BRISK
virtual ~BRISK()
Definition: Features2d.cpp:2337
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:2207
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:1104
rtabmap::ORB::patchSize_
int patchSize_
Definition: Features2d.h:340
rtabmap::ORB::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1518
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:2329
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:2621
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:2284
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:2264
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:2356
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:1853
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:1691
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:2032
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:2178
UMath.h
Basic mathematics functions.
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:506
rtabmap::KAZE::~KAZE
virtual ~KAZE()
Definition: Features2d.cpp:2392
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:2211
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:1197
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:2151
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:1514
rtabmap::FAST_FREAK
Definition: Features2d.h:406
UFATAL
#define UFATAL(...)
rtabmap::GFTT_ORB::~GFTT_ORB
virtual ~GFTT_ORB()
Definition: Features2d.cpp:2310
rtabmap::SURF_DAISY::SURF_DAISY
SURF_DAISY(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2666
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:2012
rtabmap::GFTT_BRIEF::~GFTT_BRIEF
virtual ~GFTT_BRIEF()
Definition: Features2d.cpp:2158
rtabmap::SURF_DAISY::~SURF_DAISY
virtual ~SURF_DAISY()
Definition: Features2d.cpp:2676
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:2260
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:2696
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:1255
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:2651
UConversion.h
Some conversion functions.
rtabmap::SIFT::SIFT
SIFT(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1238
rtabmap::FAST_BRIEF::FAST_BRIEF
FAST_BRIEF(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1952
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:1959
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:2434
rtabmap::SIFT
Definition: Features2d.h:287
rtabmap::GFTT::GFTT
GFTT(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2051
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:2583
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:3456
rtabmap::GFTT_ORB::GFTT_ORB
GFTT_ORB(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2303
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:1324
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:2460
rtabmap::SuperPointTorch::~SuperPointTorch
virtual ~SuperPointTorch()
Definition: Features2d.cpp:2549
UASSERT
#define UASSERT(condition)
d
d
rtabmap::FAST_FREAK::~FAST_FREAK
virtual ~FAST_FREAK()
Definition: Features2d.cpp:2008
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:2396
rtabmap::GFTT_DAISY::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2635
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:2162
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:2539
rtabmap::GFTT_FREAK::GFTT_FREAK
GFTT_FREAK(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2197
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:2231
rtabmap::SIFT::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1268
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:2606
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:1450
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
rtabmap::GFTT::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:2066
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:1116
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:2631
rtabmap::SURF_DAISY::scaleNormalized_
bool scaleNormalized_
Definition: Features2d.h:668
rtabmap::KAZE::KAZE
KAZE(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:2381
rtabmap::SIFT::edgeThreshold_
double edgeThreshold_
Definition: Features2d.h:303
rtabmap::FAST_BRIEF::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1963
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:2341
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:2449
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:2416
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:2062
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:2680
rtabmap::GFTT::_k
double _k
Definition: Features2d.h:444
rtabmap::FAST::parseParameters
virtual void parseParameters(const ParametersMap &parameters)
Definition: Features2d.cpp:1761
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:1979
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:2526
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:2483
rtabmap::ORB::ORB
ORB(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1499
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:2314
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:2370
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:2553
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:1120
rtabmap::FAST::fastCVTempBuf_
void * fastCVTempBuf_
Definition: Features2d.h:380
rtabmap::FAST_FREAK::FAST_FREAK
FAST_FREAK(const ParametersMap &parameters=ParametersMap())
Definition: Features2d.cpp:1998
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:1589
PyDetector.h
rtabmap::Feature2D::kFeatureOrbOctree
@ kFeatureOrbOctree
Definition: Features2d.h:127


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:53