#include <Orb.h>
Public Types | |
enum | { kBytes = 32, HARRIS_SCORE = 0, FAST_SCORE = 1 } |
Public Member Functions | |
CV_WRAP | CV_ORB (int nfeatures=500, float scaleFactor=1.2f, int nlevels=8, int edgeThreshold=31, int firstLevel=0, int WTA_K=2, int scoreType=CV_ORB::HARRIS_SCORE, int patchSize=31, const ParametersMap &fastParameters=ParametersMap()) |
int | descriptorSize () const |
int | descriptorType () const |
void | operator() (cv::InputArray image, cv::InputArray mask, std::vector< cv::KeyPoint > &keypoints) const |
void | operator() (cv::InputArray image, cv::InputArray mask, std::vector< cv::KeyPoint > &keypoints, cv::OutputArray descriptors, bool useProvidedKeypoints=false) const |
Protected Member Functions | |
void | computeImpl (const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors) const |
void | detectImpl (const cv::Mat &image, std::vector< cv::KeyPoint > &keypoints, const cv::Mat &mask=cv::Mat()) const |
Protected Attributes | |
CV_PROP_RW int | edgeThreshold |
ParametersMap | fastParameters |
CV_PROP_RW int | firstLevel |
CV_PROP_RW int | nfeatures |
CV_PROP_RW int | nlevels |
CV_PROP_RW int | patchSize |
CV_PROP_RW double | scaleFactor |
CV_PROP_RW int | scoreType |
CV_PROP_RW int | WTA_K |
rtabmap::CV_ORB::CV_ORB | ( | int | _nfeatures = 500 , |
float | _scaleFactor = 1.2f , |
||
int | _nlevels = 8 , |
||
int | _edgeThreshold = 31 , |
||
int | _firstLevel = 0 , |
||
int | _WTA_K = 2 , |
||
int | _scoreType = CV_ORB::HARRIS_SCORE , |
||
int | _patchSize = 31 , |
||
const ParametersMap & | _fastParameters = ParametersMap() |
||
) | [explicit] |
void rtabmap::CV_ORB::computeImpl | ( | const cv::Mat & | image, |
std::vector< cv::KeyPoint > & | keypoints, | ||
cv::Mat & | descriptors | ||
) | const [protected] |
int rtabmap::CV_ORB::descriptorSize | ( | ) | const |
int rtabmap::CV_ORB::descriptorType | ( | ) | const |
void rtabmap::CV_ORB::detectImpl | ( | const cv::Mat & | image, |
std::vector< cv::KeyPoint > & | keypoints, | ||
const cv::Mat & | mask = cv::Mat() |
||
) | const [protected] |
void rtabmap::CV_ORB::operator() | ( | cv::InputArray | image, |
cv::InputArray | mask, | ||
std::vector< cv::KeyPoint > & | keypoints | ||
) | const |
void rtabmap::CV_ORB::operator() | ( | cv::InputArray | image, |
cv::InputArray | mask, | ||
std::vector< cv::KeyPoint > & | keypoints, | ||
cv::OutputArray | descriptors, | ||
bool | useProvidedKeypoints = false |
||
) | const |
CV_PROP_RW int rtabmap::CV_ORB::edgeThreshold [protected] |
ParametersMap rtabmap::CV_ORB::fastParameters [protected] |
CV_PROP_RW int rtabmap::CV_ORB::firstLevel [protected] |
CV_PROP_RW int rtabmap::CV_ORB::nfeatures [protected] |
CV_PROP_RW int rtabmap::CV_ORB::nlevels [protected] |
CV_PROP_RW int rtabmap::CV_ORB::patchSize [protected] |
CV_PROP_RW double rtabmap::CV_ORB::scaleFactor [protected] |
CV_PROP_RW int rtabmap::CV_ORB::scoreType [protected] |
CV_PROP_RW int rtabmap::CV_ORB::WTA_K [protected] |