Base class for sparse feature extractors. More...
#include <feature_detector.h>
Public Member Functions | |
FeatureDetector () | |
Default constructor. | |
FeatureDetector () | |
Default constructor. | |
void | findFeatures (RGBDFrame &frame) |
Main function to call to detect the sparse features in an RGBDFrame and fill out the corresponding information. | |
void | findFeatures (RGBDFrame &frame) |
Main function to call to detect the sparse features in an RGBDFrame and fill out the corresponding information. | |
double | getMaxRange () const |
Returns the maximum allowed z-depth (in meters) for features. | |
double | getMaxRange () const |
Returns the maximum allowed z-depth (in meters) for features. | |
double | getMaxStDev () const |
Returns the maximum allowed std_dev(z) (in meters) for features. | |
double | getMaxStDev () const |
Returns the maximum allowed std_dev(z) (in meters) for features. | |
int | getSmooth () const |
Returns the smoothing size. | |
int | getSmooth () const |
Returns the smoothing size. | |
void | setComputeDescriptors (bool compute_descriptors) |
void | setComputeDescriptors (bool compute_descriptors) |
void | setMaxRange (double max_range) |
Sets the maximum allowed z-depth (in meters) for features. | |
void | setMaxRange (double max_range) |
Sets the maximum allowed z-depth (in meters) for features. | |
void | setMaxStDev (double max_stdev) |
Sets the maximum allowed std_dev(z) (in meters) for features. | |
void | setMaxStDev (double max_stdev) |
Sets the maximum allowed std_dev(z) (in meters) for features. | |
void | setSmooth (int smooth) |
Sets the smoothing size. | |
void | setSmooth (int smooth) |
Sets the smoothing size. | |
virtual | ~FeatureDetector () |
Default destructor. | |
virtual | ~FeatureDetector () |
Default destructor. | |
Protected Member Functions | |
virtual void | findFeatures (RGBDFrame &frame, const cv::Mat &input_img)=0 |
Implementation of the feature detector. | |
virtual void | findFeatures (RGBDFrame &frame, const cv::Mat &input_img)=0 |
Implementation of the feature detector. | |
Protected Attributes | |
bool | compute_descriptors_ |
whether to calculate feature descriptors | |
boost::mutex | mutex_ |
state mutex | |
Private Attributes | |
double | max_range_ |
maximum allowed z-depth (in meters) for features | |
double | max_stdev_ |
maximum allowed std_dev(z) (in meters) for features | |
int | smooth_ |
blurring size (blur winddow = smooth*2 + 1) |
Base class for sparse feature extractors.
Definition at line 37 of file include/rgbdtools/features/feature_detector.h.
Default constructor.
Definition at line 28 of file feature_detector.cpp.
rgbdtools::FeatureDetector::~FeatureDetector | ( | ) | [virtual] |
Default destructor.
Definition at line 37 of file feature_detector.cpp.
Default constructor.
virtual rgbdtools::FeatureDetector::~FeatureDetector | ( | ) | [virtual] |
Default destructor.
void rgbdtools::FeatureDetector::findFeatures | ( | RGBDFrame & | frame | ) |
Main function to call to detect the sparse features in an RGBDFrame and fill out the corresponding information.
frame | the input frame |
todo: maybe check type of keypoints (ORB/GFT etc), and if matches, don't clear it
Definition at line 42 of file feature_detector.cpp.
void rgbdtools::FeatureDetector::findFeatures | ( | RGBDFrame & | frame | ) |
Main function to call to detect the sparse features in an RGBDFrame and fill out the corresponding information.
frame | the input frame |
virtual void rgbdtools::FeatureDetector::findFeatures | ( | RGBDFrame & | frame, |
const cv::Mat & | input_img | ||
) | [protected, pure virtual] |
Implementation of the feature detector.
frame | the input frame |
input_img | the image for feature detection, derived from the RGB image of the frame after (optional) blurring |
Implemented in rgbdtools::GftDetector, rgbdtools::OrbDetector, rgbdtools::StarDetector, rgbdtools::SurfDetector, rgbdtools::GftDetector, rgbdtools::OrbDetector, rgbdtools::StarDetector, and rgbdtools::SurfDetector.
virtual void rgbdtools::FeatureDetector::findFeatures | ( | RGBDFrame & | frame, |
const cv::Mat & | input_img | ||
) | [protected, pure virtual] |
Implementation of the feature detector.
frame | the input frame |
input_img | the image for feature detection, derived from the RGB image of the frame after (optional) blurring |
Implemented in rgbdtools::GftDetector, rgbdtools::OrbDetector, rgbdtools::StarDetector, rgbdtools::SurfDetector, rgbdtools::GftDetector, rgbdtools::OrbDetector, rgbdtools::StarDetector, and rgbdtools::SurfDetector.
double rgbdtools::FeatureDetector::getMaxRange | ( | ) | const [inline] |
Returns the maximum allowed z-depth (in meters) for features.
Definition at line 104 of file feature_detector.cpp.
double rgbdtools::FeatureDetector::getMaxRange | ( | ) | const [inline] |
Returns the maximum allowed z-depth (in meters) for features.
double rgbdtools::FeatureDetector::getMaxStDev | ( | ) | const [inline] |
Returns the maximum allowed std_dev(z) (in meters) for features.
Definition at line 109 of file feature_detector.cpp.
double rgbdtools::FeatureDetector::getMaxStDev | ( | ) | const [inline] |
Returns the maximum allowed std_dev(z) (in meters) for features.
int rgbdtools::FeatureDetector::getSmooth | ( | ) | const [inline] |
Returns the smoothing size.
Smoothing is performed using Gaussian bluring in a window of size smooth*2 + 1
If smooth is set to 0, then no blurring will take place
Definition at line 99 of file feature_detector.cpp.
int rgbdtools::FeatureDetector::getSmooth | ( | ) | const [inline] |
Returns the smoothing size.
Smoothing is performed using Gaussian bluring in a window of size smooth*2 + 1
If smooth is set to 0, then no blurring will take place
void rgbdtools::FeatureDetector::setComputeDescriptors | ( | bool | compute_descriptors | ) |
Definition at line 79 of file feature_detector.cpp.
void rgbdtools::FeatureDetector::setComputeDescriptors | ( | bool | compute_descriptors | ) |
void rgbdtools::FeatureDetector::setMaxRange | ( | double | max_range | ) |
Sets the maximum allowed z-depth (in meters) for features.
max_range | maximum allowed z-depth (in meters) for features |
void rgbdtools::FeatureDetector::setMaxRange | ( | double | max_range | ) |
Sets the maximum allowed z-depth (in meters) for features.
max_range | maximum allowed z-depth (in meters) for features |
Definition at line 89 of file feature_detector.cpp.
void rgbdtools::FeatureDetector::setMaxStDev | ( | double | max_stdev | ) |
Sets the maximum allowed std_dev(z) (in meters) for features.
max_stdev | maximum allowed std_dev(z) (in meters) for features |
void rgbdtools::FeatureDetector::setMaxStDev | ( | double | max_stdev | ) |
Sets the maximum allowed std_dev(z) (in meters) for features.
max_stdev | maximum allowed std_dev(z) (in meters) for features |
Definition at line 94 of file feature_detector.cpp.
void rgbdtools::FeatureDetector::setSmooth | ( | int | smooth | ) |
Sets the smoothing size.
Smoothing is performed using Gaussian bluring in a window of size smooth*2 + 1
If smooth is set to 0, then no blurring will take place
smooth | smoothing window size |
void rgbdtools::FeatureDetector::setSmooth | ( | int | smooth | ) |
Sets the smoothing size.
Smoothing is performed using Gaussian bluring in a window of size smooth*2 + 1
If smooth is set to 0, then no blurring will take place
smooth | smoothing window size |
Definition at line 84 of file feature_detector.cpp.
bool rgbdtools::FeatureDetector::compute_descriptors_ [protected] |
whether to calculate feature descriptors
Definition at line 103 of file include/rgbdtools/features/feature_detector.h.
double rgbdtools::FeatureDetector::max_range_ [private] |
maximum allowed z-depth (in meters) for features
Definition at line 115 of file include/rgbdtools/features/feature_detector.h.
double rgbdtools::FeatureDetector::max_stdev_ [private] |
maximum allowed std_dev(z) (in meters) for features
Definition at line 116 of file include/rgbdtools/features/feature_detector.h.
boost::mutex rgbdtools::FeatureDetector::mutex_ [protected] |
state mutex
Definition at line 101 of file include/rgbdtools/features/feature_detector.h.
int rgbdtools::FeatureDetector::smooth_ [private] |
blurring size (blur winddow = smooth*2 + 1)
Definition at line 114 of file include/rgbdtools/features/feature_detector.h.