#include <rgb_feature_matcher.h>
| Public Member Functions | |
| void | findMatches (const cv::Mat &source_descriptors, const cv::Mat &target_descriptors, std::vector< cv::DMatch > &matches) | 
| bool | getMatches (std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &source_inlier_3d_locations, std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > &target_inlier_3d_locations, Eigen::Matrix4f &ransac_trafo) | 
| PointCloudConstPtr | getSourceCloud () | 
| cv::Mat | getSourceImage () | 
| PointCloudConstPtr | getTargetCloud () | 
| cv::Mat | getTargetImage () | 
| void | OutlierRemoval (const std::vector< cv::DMatch > &matches, std::vector< cv::DMatch > &good_matches) | 
| cv::Mat | restoreCVMatFromPointCloud (PointCloudConstPtr cloud_in) | 
| RGBFeatureMatcher () | |
| RGBFeatureMatcher (PointCloudPtr source_cloud_ptr, PointCloudPtr target_cloud_ptr) | |
| RGBFeatureMatcher (PointCloudPtr source_cloud_ptr, PointCloudPtr target_cloud_ptr, const cv::Mat &source_image, const cv::Mat &target_image) | |
| void | setSourceCloud (const PointCloudPtr source_cloud) | 
| void | setSourceImage (const cv::Mat &source_image) | 
| void | setTargetCloud (const PointCloudPtr target_cloud) | 
| void | setTargetImage (const cv::Mat &target_image) | 
| virtual | ~RGBFeatureMatcher () | 
| Private Attributes | |
| PointCloudConstPtr | source_cloud_ptr_ | 
| cv::Mat | source_image_ | 
| PointCloudConstPtr | target_cloud_ptr_ | 
| cv::Mat | target_image_ | 
Definition at line 14 of file rgb_feature_matcher.h.
Definition at line 34 of file rgb_feature_matcher.cpp.
| RGBFeatureMatcher::RGBFeatureMatcher | ( | PointCloudPtr | source_cloud_ptr, | 
| PointCloudPtr | target_cloud_ptr | ||
| ) | 
Definition at line 17 of file rgb_feature_matcher.cpp.
| RGBFeatureMatcher::RGBFeatureMatcher | ( | PointCloudPtr | source_cloud_ptr, | 
| PointCloudPtr | target_cloud_ptr, | ||
| const cv::Mat & | source_image, | ||
| const cv::Mat & | target_image | ||
| ) | 
Definition at line 27 of file rgb_feature_matcher.cpp.
| RGBFeatureMatcher::~RGBFeatureMatcher | ( | ) |  [virtual] | 
Definition at line 39 of file rgb_feature_matcher.cpp.
| void RGBFeatureMatcher::findMatches | ( | const cv::Mat & | source_descriptors, | 
| const cv::Mat & | target_descriptors, | ||
| std::vector< cv::DMatch > & | matches | ||
| ) | 
Definition at line 170 of file rgb_feature_matcher.cpp.
| bool RGBFeatureMatcher::getMatches | ( | std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > & | source_inlier_3d_locations, | 
| std::vector< Eigen::Vector4f, Eigen::aligned_allocator< Eigen::Vector4f > > & | target_inlier_3d_locations, | ||
| Eigen::Matrix4f & | ransac_trafo | ||
| ) | 
Definition at line 97 of file rgb_feature_matcher.cpp.
Definition at line 49 of file rgb_feature_matcher.cpp.
| cv::Mat RGBFeatureMatcher::getSourceImage | ( | ) | 
Definition at line 68 of file rgb_feature_matcher.cpp.
Definition at line 59 of file rgb_feature_matcher.cpp.
| cv::Mat RGBFeatureMatcher::getTargetImage | ( | ) | 
Definition at line 76 of file rgb_feature_matcher.cpp.
| void RGBFeatureMatcher::OutlierRemoval | ( | const std::vector< cv::DMatch > & | matches, | 
| std::vector< cv::DMatch > & | good_matches | ||
| ) | 
Definition at line 188 of file rgb_feature_matcher.cpp.
| cv::Mat RGBFeatureMatcher::restoreCVMatFromPointCloud | ( | PointCloudConstPtr | cloud_in | ) | 
Definition at line 81 of file rgb_feature_matcher.cpp.
| void RGBFeatureMatcher::setSourceCloud | ( | const PointCloudPtr | source_cloud | ) | 
Definition at line 44 of file rgb_feature_matcher.cpp.
| void RGBFeatureMatcher::setSourceImage | ( | const cv::Mat & | source_image | ) | 
Definition at line 64 of file rgb_feature_matcher.cpp.
| void RGBFeatureMatcher::setTargetCloud | ( | const PointCloudPtr | target_cloud | ) | 
Definition at line 54 of file rgb_feature_matcher.cpp.
| void RGBFeatureMatcher::setTargetImage | ( | const cv::Mat & | target_image | ) | 
Definition at line 72 of file rgb_feature_matcher.cpp.
Definition at line 50 of file rgb_feature_matcher.h.
| cv::Mat RGBFeatureMatcher::source_image_  [private] | 
Definition at line 51 of file rgb_feature_matcher.h.
Definition at line 50 of file rgb_feature_matcher.h.
| cv::Mat RGBFeatureMatcher::target_image_  [private] | 
Definition at line 51 of file rgb_feature_matcher.h.