#include <jockey.h>
Public Member Functions | |
std::string | getLearningJockeyName () const |
std::string | getNavigatingJockeyName () const |
Jockey (const std::string &name) | |
Private Member Functions | |
void | extractFeatures (const sensor_msgs::ImageConstPtr &image, vector< KeyPoint > &keypoints, vector< Feature > &descriptors) const |
void | initDetectorDense () |
void | initDetectorFast () |
void | initDetectorGftt () |
void | initDetectorMser () |
void | initDetectorOrb () |
void | initDetectorSimpleblob () |
void | initDetectorStar () |
void | initExtractorBrief () |
void | initExtractorOrb () |
void | initMatcherBruteforce () |
void | initMatcherFlannbased () |
void | matchDescriptors (const vector< Feature > &query_descriptors, const vector< Feature > &train_descriptors, vector< vector< DMatch > > &matches) const |
Private Attributes | |
boost::scoped_ptr < featurenav_base::ANJockey > | anjockey_ptr_ |
> The base name for learning and navigating jockeys. | |
std::string | base_name_ |
boost::scoped_ptr < cv::DescriptorExtractor > | descriptor_extractor_ |
std::string | descriptor_extractor_code_ |
std::string | descriptor_extractor_type_ |
boost::scoped_ptr < cv::DescriptorMatcher > | descriptor_matcher_ |
std::string | descriptor_matcher_code_ |
std::string | descriptor_matcher_type_ |
boost::scoped_ptr < cv::FeatureDetector > | feature_detector_ |
std::string | feature_detector_code_ |
std::string | feature_detector_type_ |
std::string | map_interface_name_ |
ros::NodeHandle | private_nh_ |
anj_featurenav::Jockey::Jockey | ( | const std::string & | name | ) |
Definition at line 15 of file jockey.cpp.
void anj_featurenav::Jockey::extractFeatures | ( | const sensor_msgs::ImageConstPtr & | image, |
vector< KeyPoint > & | keypoints, | ||
vector< Feature > & | descriptors | ||
) | const [private] |
Definition at line 327 of file jockey.cpp.
std::string anj_featurenav::Jockey::getLearningJockeyName | ( | ) | const |
Definition at line 124 of file jockey.cpp.
std::string anj_featurenav::Jockey::getNavigatingJockeyName | ( | ) | const |
Definition at line 133 of file jockey.cpp.
void anj_featurenav::Jockey::initDetectorDense | ( | ) | [private] |
Definition at line 231 of file jockey.cpp.
void anj_featurenav::Jockey::initDetectorFast | ( | ) | [private] |
Definition at line 144 of file jockey.cpp.
void anj_featurenav::Jockey::initDetectorGftt | ( | ) | [private] |
Definition at line 215 of file jockey.cpp.
void anj_featurenav::Jockey::initDetectorMser | ( | ) | [private] |
Definition at line 195 of file jockey.cpp.
void anj_featurenav::Jockey::initDetectorOrb | ( | ) | [private] |
Definition at line 171 of file jockey.cpp.
void anj_featurenav::Jockey::initDetectorSimpleblob | ( | ) | [private] |
Definition at line 249 of file jockey.cpp.
void anj_featurenav::Jockey::initDetectorStar | ( | ) | [private] |
Definition at line 156 of file jockey.cpp.
void anj_featurenav::Jockey::initExtractorBrief | ( | ) | [private] |
Definition at line 281 of file jockey.cpp.
void anj_featurenav::Jockey::initExtractorOrb | ( | ) | [private] |
Definition at line 257 of file jockey.cpp.
void anj_featurenav::Jockey::initMatcherBruteforce | ( | ) | [private] |
Definition at line 289 of file jockey.cpp.
void anj_featurenav::Jockey::initMatcherFlannbased | ( | ) | [private] |
Definition at line 321 of file jockey.cpp.
void anj_featurenav::Jockey::matchDescriptors | ( | const vector< Feature > & | query_descriptors, |
const vector< Feature > & | train_descriptors, | ||
vector< vector< DMatch > > & | matches | ||
) | const [private] |
Definition at line 347 of file jockey.cpp.
boost::scoped_ptr<featurenav_base::ANJockey> anj_featurenav::Jockey::anjockey_ptr_ [private] |
std::string anj_featurenav::Jockey::base_name_ [private] |
boost::scoped_ptr<cv::DescriptorExtractor> anj_featurenav::Jockey::descriptor_extractor_ [private] |
std::string anj_featurenav::Jockey::descriptor_extractor_code_ [private] |
std::string anj_featurenav::Jockey::descriptor_extractor_type_ [private] |
boost::scoped_ptr<cv::DescriptorMatcher> anj_featurenav::Jockey::descriptor_matcher_ [private] |
std::string anj_featurenav::Jockey::descriptor_matcher_code_ [private] |
std::string anj_featurenav::Jockey::descriptor_matcher_type_ [private] |
boost::scoped_ptr<cv::FeatureDetector> anj_featurenav::Jockey::feature_detector_ [private] |
std::string anj_featurenav::Jockey::feature_detector_code_ [private] |
std::string anj_featurenav::Jockey::feature_detector_type_ [private] |
std::string anj_featurenav::Jockey::map_interface_name_ [private] |