ORBextractor.h
Go to the documentation of this file.
1 
29 #ifndef RTABMAP_ORBEXTRACTOR_H
30 #define RTABMAP_ORBEXTRACTOR_H
31 
32 #include <vector>
33 #include <list>
34 #include <opencv2/core/core_c.h>
35 
36 
37 namespace rtabmap
38 {
39 
41 {
42 public:
44 
46 
47  std::vector<cv::KeyPoint> vKeys;
48  cv::Point2i UL, UR, BL, BR;
49  std::list<ExtractorNode>::iterator lit;
50  bool bNoMore;
51 };
52 
54 {
55 public:
56 
57  enum {HARRIS_SCORE=0, FAST_SCORE=1 };
58 
59  ORBextractor(int nfeatures, float scaleFactor, int nlevels,
60  int iniThFAST, int minThFAST, int patchSize, int edgeThreshold);
61 
63 
64  // Compute the ORB features and descriptors on an image.
65  // ORB are dispersed on the image using an octree.
66  // Mask is ignored in the current implementation.
67  void operator()( cv::InputArray image, cv::InputArray mask,
68  std::vector<cv::KeyPoint>& keypoints,
69  cv::OutputArray descriptors);
70 
71  int inline GetLevels(){
72  return nlevels;}
73 
74  float inline GetScaleFactor(){
75  return scaleFactor;}
76 
77  std::vector<float> inline GetScaleFactors(){
78  return mvScaleFactor;
79  }
80 
81  std::vector<float> inline GetInverseScaleFactors(){
82  return mvInvScaleFactor;
83  }
84 
85  std::vector<float> inline GetScaleSigmaSquares(){
86  return mvLevelSigma2;
87  }
88 
89  std::vector<float> inline GetInverseScaleSigmaSquares(){
90  return mvInvLevelSigma2;
91  }
92 
93  std::vector<cv::Mat> mvImagePyramid;
94 
95 protected:
96 
97  void ComputePyramid(cv::Mat image);
98  void ComputeKeyPointsOctTree(std::vector<std::vector<cv::KeyPoint> >& allKeypoints);
99  std::vector<cv::KeyPoint> DistributeOctTree(const std::vector<cv::KeyPoint>& vToDistributeKeys, const int &minX,
100  const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level);
101 
102  void ComputeKeyPointsOld(std::vector<std::vector<cv::KeyPoint> >& allKeypoints);
103  std::vector<cv::Point> pattern;
104 
106  double scaleFactor;
107  int nlevels;
113 
114 
115  std::vector<int> mnFeaturesPerLevel;
116 
117  std::vector<int> umax;
118 
119  std::vector<float> mvScaleFactor;
120  std::vector<float> mvInvScaleFactor;
121  std::vector<float> mvLevelSigma2;
122  std::vector<float> mvInvLevelSigma2;
123 };
124 
125 } //namespace rtabmap
126 
127 #endif
128 
rtabmap::ORBextractor::mvScaleFactor
std::vector< float > mvScaleFactor
Definition: ORBextractor.h:119
glm::mask
GLM_FUNC_DECL genIType mask(genIType const &count)
rtabmap::ORBextractor::nlevels
int nlevels
Definition: ORBextractor.h:107
rtabmap::ORBextractor::GetScaleFactors
std::vector< float > GetScaleFactors()
Definition: ORBextractor.h:77
rtabmap::ORBextractor::mvInvLevelSigma2
std::vector< float > mvInvLevelSigma2
Definition: ORBextractor.h:122
rtabmap::ORBextractor::mvInvScaleFactor
std::vector< float > mvInvScaleFactor
Definition: ORBextractor.h:120
rtabmap::ORBextractor::DistributeOctTree
std::vector< cv::KeyPoint > DistributeOctTree(const std::vector< cv::KeyPoint > &vToDistributeKeys, const int &minX, const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level)
Definition: ORBextractor.cc:546
rtabmap::ExtractorNode::UR
cv::Point2i UR
Definition: ORBextractor.h:48
rtabmap::ORBextractor::operator()
void operator()(cv::InputArray image, cv::InputArray mask, std::vector< cv::KeyPoint > &keypoints, cv::OutputArray descriptors)
Definition: ORBextractor.cc:1050
rtabmap::ORBextractor::ComputeKeyPointsOctTree
void ComputeKeyPointsOctTree(std::vector< std::vector< cv::KeyPoint > > &allKeypoints)
Definition: ORBextractor.cc:772
rtabmap::ORBextractor::HARRIS_SCORE
@ HARRIS_SCORE
Definition: ORBextractor.h:57
rtabmap::ORBextractor::scaleFactor
double scaleFactor
Definition: ORBextractor.h:106
rtabmap::ORBextractor::halfPatchSize
int halfPatchSize
Definition: ORBextractor.h:112
rtabmap::ORBextractor
Definition: ORBextractor.h:53
rtabmap::ExtractorNode::BL
cv::Point2i BL
Definition: ORBextractor.h:48
rtabmap::ExtractorNode
Definition: ORBextractor.h:40
rtabmap::ExtractorNode::bNoMore
bool bNoMore
Definition: ORBextractor.h:50
rtabmap::ORBextractor::GetScaleSigmaSquares
std::vector< float > GetScaleSigmaSquares()
Definition: ORBextractor.h:85
rtabmap::ORBextractor::mvImagePyramid
std::vector< cv::Mat > mvImagePyramid
Definition: ORBextractor.h:93
rtabmap::ORBextractor::pattern
std::vector< cv::Point > pattern
Definition: ORBextractor.h:103
rtabmap::ExtractorNode::lit
std::list< ExtractorNode >::iterator lit
Definition: ORBextractor.h:49
rtabmap::ExtractorNode::vKeys
std::vector< cv::KeyPoint > vKeys
Definition: ORBextractor.h:47
rtabmap::ORBextractor::GetInverseScaleFactors
std::vector< float > GetInverseScaleFactors()
Definition: ORBextractor.h:81
rtabmap::ORBextractor::umax
std::vector< int > umax
Definition: ORBextractor.h:117
rtabmap::ORBextractor::~ORBextractor
~ORBextractor()
Definition: ORBextractor.h:62
rtabmap::ORBextractor::GetInverseScaleSigmaSquares
std::vector< float > GetInverseScaleSigmaSquares()
Definition: ORBextractor.h:89
rtabmap::ORBextractor::minThFAST
int minThFAST
Definition: ORBextractor.h:109
rtabmap::ORBextractor::nfeatures
int nfeatures
Definition: ORBextractor.h:105
rtabmap::ORBextractor::ComputeKeyPointsOld
void ComputeKeyPointsOld(std::vector< std::vector< cv::KeyPoint > > &allKeypoints)
Definition: ORBextractor.cc:862
rtabmap::ORBextractor::edgeThreshold
int edgeThreshold
Definition: ORBextractor.h:111
rtabmap::ExtractorNode::BR
cv::Point2i BR
Definition: ORBextractor.h:48
rtabmap::ORBextractor::iniThFAST
int iniThFAST
Definition: ORBextractor.h:108
rtabmap::ORBextractor::GetScaleFactor
float GetScaleFactor()
Definition: ORBextractor.h:74
rtabmap::ORBextractor::ComputePyramid
void ComputePyramid(cv::Mat image)
Definition: ORBextractor.cc:1114
rtabmap::ExtractorNode::UL
cv::Point2i UL
Definition: ORBextractor.h:48
rtabmap::ORBextractor::GetLevels
int GetLevels()
Definition: ORBextractor.h:71
rtabmap::ORBextractor::FAST_SCORE
@ FAST_SCORE
Definition: ORBextractor.h:57
rtabmap::ORBextractor::mvLevelSigma2
std::vector< float > mvLevelSigma2
Definition: ORBextractor.h:121
rtabmap::ORBextractor::patchSize
int patchSize
Definition: ORBextractor.h:110
false
#define false
Definition: ConvertUTF.c:56
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::ExtractorNode::DivideNode
void DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4)
Definition: ORBextractor.cc:488
rtabmap::ORBextractor::mnFeaturesPerLevel
std::vector< int > mnFeaturesPerLevel
Definition: ORBextractor.h:115
rtabmap::ExtractorNode::ExtractorNode
ExtractorNode()
Definition: ORBextractor.h:43
rtabmap::ORBextractor::ORBextractor
ORBextractor(int nfeatures, float scaleFactor, int nlevels, int iniThFAST, int minThFAST, int patchSize, int edgeThreshold)
Definition: ORBextractor.cc:416


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:14