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()) const
 
std::vector< cv::Point3f > generateKeypoints3D (const SensorData &data, const std::vector< cv::KeyPoint > &keypoints) const
 
float getMaxDepth () const
 
int getMaxFeatures () const
 
float getMinDepth () const
 
virtual const ParametersMapgetParameters () 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()) const
 

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
}
 
- 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 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 (std::vector< cv::KeyPoint > &keypoints, int maxKeypoints)
 
static void limitKeypoints (std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors, int maxKeypoints)
 
static void limitKeypoints (std::vector< cv::KeyPoint > &keypoints, std::vector< cv::Point3f > &keypoints3D, cv::Mat &descriptors, int maxKeypoints)
 
static void limitKeypoints (const std::vector< cv::KeyPoint > &keypoints, std::vector< bool > &inliers, int maxKeypoints)
 
- Protected Member Functions inherited from rtabmap::Feature2D
 Feature2D (const ParametersMap &parameters=ParametersMap())
 

Detailed Description

Definition at line 237 of file Features2d.h.

Constructor & Destructor Documentation

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

Definition at line 869 of file Features2d.cpp.

rtabmap::ORB::~ORB ( )
virtual

Definition at line 884 of file Features2d.cpp.

Member Function Documentation

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

Implements rtabmap::Feature2D.

Definition at line 999 of file Features2d.cpp.

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

Implements rtabmap::Feature2D.

Definition at line 957 of file Features2d.cpp.

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

Implements rtabmap::Feature2D.

Definition at line 244 of file Features2d.h.

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

Reimplemented from rtabmap::Feature2D.

Definition at line 888 of file Features2d.cpp.

Member Data Documentation

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

Definition at line 264 of file Features2d.h.

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

Definition at line 263 of file Features2d.h.

int rtabmap::ORB::edgeThreshold_
private

Definition at line 253 of file Features2d.h.

int rtabmap::ORB::fastThreshold_
private

Definition at line 260 of file Features2d.h.

int rtabmap::ORB::firstLevel_
private

Definition at line 254 of file Features2d.h.

bool rtabmap::ORB::gpu_
private

Definition at line 258 of file Features2d.h.

int rtabmap::ORB::nLevels_
private

Definition at line 252 of file Features2d.h.

bool rtabmap::ORB::nonmaxSuppresion_
private

Definition at line 261 of file Features2d.h.

int rtabmap::ORB::patchSize_
private

Definition at line 257 of file Features2d.h.

float rtabmap::ORB::scaleFactor_
private

Definition at line 251 of file Features2d.h.

int rtabmap::ORB::scoreType_
private

Definition at line 256 of file Features2d.h.

int rtabmap::ORB::WTA_K_
private

Definition at line 255 of file Features2d.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:43