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

#include <Features2d.h>

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

Public Member Functions

virtual Feature2D::Type getType () const
 
 ORB (const ParametersMap &parameters=ParametersMap())
 
virtual void parseParameters (const ParametersMap &parameters)
 
virtual ~ORB ()
 
- 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

cv::Ptr< CV_ORB_GPU_gpuOrb
 
cv::Ptr< CV_ORB_orb
 
int edgeThreshold_
 
int fastThreshold_
 
int firstLevel_
 
bool gpu_
 
int nLevels_
 
bool nonmaxSuppresion_
 
int patchSize_
 
float scaleFactor_
 
int scoreType_
 
int WTA_K_
 

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 303 of file Features2d.h.

Constructor & Destructor Documentation

◆ ORB()

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

Definition at line 1236 of file Features2d.cpp.

◆ ~ORB()

rtabmap::ORB::~ORB ( )
virtual

Definition at line 1251 of file Features2d.cpp.

Member Function Documentation

◆ generateDescriptorsImpl()

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

Implements rtabmap::Feature2D.

Definition at line 1368 of file Features2d.cpp.

◆ generateKeypointsImpl()

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

Implements rtabmap::Feature2D.

Definition at line 1326 of file Features2d.cpp.

◆ getType()

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

Implements rtabmap::Feature2D.

Definition at line 310 of file Features2d.h.

◆ parseParameters()

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

Reimplemented from rtabmap::Feature2D.

Definition at line 1255 of file Features2d.cpp.

Member Data Documentation

◆ _gpuOrb

cv::Ptr<CV_ORB_GPU> rtabmap::ORB::_gpuOrb
private

Definition at line 330 of file Features2d.h.

◆ _orb

cv::Ptr<CV_ORB> rtabmap::ORB::_orb
private

Definition at line 329 of file Features2d.h.

◆ edgeThreshold_

int rtabmap::ORB::edgeThreshold_
private

Definition at line 319 of file Features2d.h.

◆ fastThreshold_

int rtabmap::ORB::fastThreshold_
private

Definition at line 326 of file Features2d.h.

◆ firstLevel_

int rtabmap::ORB::firstLevel_
private

Definition at line 320 of file Features2d.h.

◆ gpu_

bool rtabmap::ORB::gpu_
private

Definition at line 324 of file Features2d.h.

◆ nLevels_

int rtabmap::ORB::nLevels_
private

Definition at line 318 of file Features2d.h.

◆ nonmaxSuppresion_

bool rtabmap::ORB::nonmaxSuppresion_
private

Definition at line 327 of file Features2d.h.

◆ patchSize_

int rtabmap::ORB::patchSize_
private

Definition at line 323 of file Features2d.h.

◆ scaleFactor_

float rtabmap::ORB::scaleFactor_
private

Definition at line 317 of file Features2d.h.

◆ scoreType_

int rtabmap::ORB::scoreType_
private

Definition at line 322 of file Features2d.h.

◆ WTA_K_

int rtabmap::ORB::WTA_K_
private

Definition at line 321 of file Features2d.h.


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


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