#include <rgb_feature_detection.h>
Public Member Functions | |
void | detectFeatures (const cv::Mat &input_image, std::vector< cv::KeyPoint > &keypoints) |
void | extractFeatures (const cv::Mat &input_image, std::vector< cv::KeyPoint > &keypoints, cv::Mat &descriptors) |
void | findMatches (const cv::Mat &source_descriptors, const cv::Mat &target_descriptors, std::vector< cv::DMatch > &good_matches) |
void | OutlierRemoval (const std::vector< cv::DMatch > &matches, std::vector< cv::DMatch > &good_matches) |
void | projectFeaturesTo3D (std::vector< cv::KeyPoint > &feature_locations_2d, std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &feature_locations_3d, const PointCloudConstPtr point_cloud) |
cv::Mat | restoreCVMatFromPointCloud (PointCloudConstPtr cloud_in) |
RGBFeatureDetection () | |
virtual | ~RGBFeatureDetection () |
Private Attributes | |
int | image_counter_ |
Definition at line 16 of file rgb_feature_detection.h.
Definition at line 20 of file rgb_feature_detection.cpp.
RGBFeatureDetection::~RGBFeatureDetection | ( | ) | [virtual] |
Definition at line 25 of file rgb_feature_detection.cpp.
void RGBFeatureDetection::detectFeatures | ( | const cv::Mat & | input_image, |
std::vector< cv::KeyPoint > & | keypoints | ||
) |
Definition at line 61 of file rgb_feature_detection.cpp.
void RGBFeatureDetection::extractFeatures | ( | const cv::Mat & | input_image, |
std::vector< cv::KeyPoint > & | keypoints, | ||
cv::Mat & | descriptors | ||
) |
Definition at line 77 of file rgb_feature_detection.cpp.
void RGBFeatureDetection::findMatches | ( | const cv::Mat & | source_descriptors, |
const cv::Mat & | target_descriptors, | ||
std::vector< cv::DMatch > & | good_matches | ||
) |
void RGBFeatureDetection::OutlierRemoval | ( | const std::vector< cv::DMatch > & | matches, |
std::vector< cv::DMatch > & | good_matches | ||
) |
void RGBFeatureDetection::projectFeaturesTo3D | ( | std::vector< cv::KeyPoint > & | feature_locations_2d, |
std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > & | feature_locations_3d, | ||
const PointCloudConstPtr | point_cloud | ||
) |
Definition at line 34 of file rgb_feature_detection.cpp.
cv::Mat RGBFeatureDetection::restoreCVMatFromPointCloud | ( | PointCloudConstPtr | cloud_in | ) |
int RGBFeatureDetection::image_counter_ [private] |
Definition at line 40 of file rgb_feature_detection.h.