Public Member Functions | Private Member Functions | Private Attributes | List of all members
rtabmap::SIFT Class Reference

#include <Features2d.h>

Inheritance diagram for rtabmap::SIFT:
Inheritance graph
[legend]

Public Member Functions

virtual Feature2D::Type getType () const
 
virtual void parseParameters (const ParametersMap &parameters)
 
 SIFT (const ParametersMap &parameters=ParametersMap())
 
virtual ~SIFT ()
 
- Public Member Functions inherited from rtabmap::Feature2D
cv::Mat generateDescriptors (const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
 
std::vector< cv::KeyPoint > generateKeypoints (const cv::Mat &image, const cv::Mat &mask=cv::Mat())
 
std::vector< cv::Point3f > generateKeypoints3D (const SensorData &data, const std::vector< cv::KeyPoint > &keypoints) const
 
int getGridCols () const
 
int getGridRows () const
 
float getMaxDepth () const
 
int getMaxFeatures () const
 
float getMinDepth () const
 
virtual const ParametersMapgetParameters () const
 
bool getSSC () const
 
virtual ~Feature2D ()
 

Private Member Functions

virtual cv::Mat generateDescriptorsImpl (const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints) const
 
virtual std::vector< cv::KeyPoint > generateKeypointsImpl (const cv::Mat &image, const cv::Rect &roi, const cv::Mat &mask=cv::Mat())
 

Private Attributes

double contrastThreshold_
 
SiftData * cudaSiftData_
 
cv::Mat cudaSiftDescriptors_
 
floatcudaSiftMemory_
 
cv::Size cudaSiftMemorySize_
 
bool cudaSiftUpscaling_
 
double edgeThreshold_
 
bool gpu_
 
float guaussianThreshold_
 
int nOctaveLayers_
 
bool preciseUpscale_
 
bool rootSIFT_
 
cv::Ptr< CV_SIFTsift_
 
double sigma_
 
bool upscale_
 

Additional Inherited Members

- Public Types inherited from rtabmap::Feature2D
enum  Type {
  kFeatureUndef =-1, kFeatureSurf =0, kFeatureSift =1, kFeatureOrb =2,
  kFeatureFastFreak =3, kFeatureFastBrief =4, kFeatureGfttFreak =5, kFeatureGfttBrief =6,
  kFeatureBrisk =7, kFeatureGfttOrb =8, kFeatureKaze =9, kFeatureOrbOctree =10,
  kFeatureSuperPointTorch =11, kFeatureSurfFreak =12, kFeatureGfttDaisy =13, kFeatureSurfDaisy =14,
  kFeaturePyDetector =15
}
 
- Static Public Member Functions inherited from rtabmap::Feature2D
static cv::Rect computeRoi (const cv::Mat &image, const std::string &roiRatios)
 
static cv::Rect computeRoi (const cv::Mat &image, const std::vector< float > &roiRatios)
 
static Feature2Dcreate (const ParametersMap &parameters=ParametersMap())
 
static Feature2Dcreate (Feature2D::Type type, const ParametersMap &parameters=ParametersMap())
 
static void filterKeypointsByDepth (std::vector< cv::KeyPoint > &keypoints, const cv::Mat &depth, float minDepth, float maxDepth)
 
static void filterKeypointsByDepth (std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &depth, float minDepth, float maxDepth)
 
static void filterKeypointsByDepth (std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, std::vector< cv::Point3f > &keypoints3D, float minDepth, float maxDepth)
 
static void filterKeypointsByDisparity (std::vector< cv::KeyPoint > &keypoints, const cv::Mat &disparity, float minDisparity)
 
static void filterKeypointsByDisparity (std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, const cv::Mat &disparity, float minDisparity)
 
static void limitKeypoints (const std::vector< cv::KeyPoint > &keypoints, std::vector< bool > &inliers, int maxKeypoints, const cv::Size &imageSize, int gridRows, int gridCols, bool ssc=false)
 
static void limitKeypoints (const std::vector< cv::KeyPoint > &keypoints, std::vector< bool > &inliers, int maxKeypoints, const cv::Size &imageSize=cv::Size(), bool ssc=false)
 
static void limitKeypoints (std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, int maxKeypoints, const cv::Size &imageSize=cv::Size(), bool ssc=false)
 
static void limitKeypoints (std::vector< cv::KeyPoint > &keypoints, int maxKeypoints, const cv::Size &imageSize=cv::Size(), bool ssc=false)
 
static void limitKeypoints (std::vector< cv::KeyPoint > &keypoints, std::vector< cv::Point3f > &keypoints3D, cv::Mat &descriptors, int maxKeypoints, const cv::Size &imageSize=cv::Size(), bool ssc=false)
 
static std::string typeName (Type type)
 
- Protected Member Functions inherited from rtabmap::Feature2D
 Feature2D (const ParametersMap &parameters=ParametersMap())
 

Detailed Description

Definition at line 287 of file Features2d.h.

Constructor & Destructor Documentation

◆ SIFT()

rtabmap::SIFT::SIFT ( const ParametersMap parameters = ParametersMap())

Definition at line 1227 of file Features2d.cpp.

◆ ~SIFT()

rtabmap::SIFT::~SIFT ( )
virtual

Definition at line 1244 of file Features2d.cpp.

Member Function Documentation

◆ generateDescriptorsImpl()

cv::Mat rtabmap::SIFT::generateDescriptorsImpl ( const cv::Mat image,
std::vector< cv::KeyPoint > &  keypoints 
) const
privatevirtual

Implements rtabmap::Feature2D.

Definition at line 1434 of file Features2d.cpp.

◆ generateKeypointsImpl()

std::vector< cv::KeyPoint > rtabmap::SIFT::generateKeypointsImpl ( const cv::Mat image,
const cv::Rect &  roi,
const cv::Mat mask = cv::Mat() 
)
privatevirtual

Implements rtabmap::Feature2D.

Definition at line 1313 of file Features2d.cpp.

◆ getType()

virtual Feature2D::Type rtabmap::SIFT::getType ( ) const
inlinevirtual

Implements rtabmap::Feature2D.

Definition at line 294 of file Features2d.h.

◆ parseParameters()

void rtabmap::SIFT::parseParameters ( const ParametersMap parameters)
virtual

Reimplemented from rtabmap::Feature2D.

Definition at line 1257 of file Features2d.cpp.

Member Data Documentation

◆ contrastThreshold_

double rtabmap::SIFT::contrastThreshold_
private

Definition at line 302 of file Features2d.h.

◆ cudaSiftData_

SiftData* rtabmap::SIFT::cudaSiftData_
private

Definition at line 312 of file Features2d.h.

◆ cudaSiftDescriptors_

cv::Mat rtabmap::SIFT::cudaSiftDescriptors_
private

Definition at line 315 of file Features2d.h.

◆ cudaSiftMemory_

float* rtabmap::SIFT::cudaSiftMemory_
private

Definition at line 313 of file Features2d.h.

◆ cudaSiftMemorySize_

cv::Size rtabmap::SIFT::cudaSiftMemorySize_
private

Definition at line 314 of file Features2d.h.

◆ cudaSiftUpscaling_

bool rtabmap::SIFT::cudaSiftUpscaling_
private

Definition at line 316 of file Features2d.h.

◆ edgeThreshold_

double rtabmap::SIFT::edgeThreshold_
private

Definition at line 303 of file Features2d.h.

◆ gpu_

bool rtabmap::SIFT::gpu_
private

Definition at line 307 of file Features2d.h.

◆ guaussianThreshold_

float rtabmap::SIFT::guaussianThreshold_
private

Definition at line 308 of file Features2d.h.

◆ nOctaveLayers_

int rtabmap::SIFT::nOctaveLayers_
private

Definition at line 301 of file Features2d.h.

◆ preciseUpscale_

bool rtabmap::SIFT::preciseUpscale_
private

Definition at line 305 of file Features2d.h.

◆ rootSIFT_

bool rtabmap::SIFT::rootSIFT_
private

Definition at line 306 of file Features2d.h.

◆ sift_

cv::Ptr<CV_SIFT> rtabmap::SIFT::sift_
private

Definition at line 311 of file Features2d.h.

◆ sigma_

double rtabmap::SIFT::sigma_
private

Definition at line 304 of file Features2d.h.

◆ upscale_

bool rtabmap::SIFT::upscale_
private

Definition at line 309 of file Features2d.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:43:04