rgb_feature_matcher.h
Go to the documentation of this file.
00001 /*
00002  * RGB_feature_matcher.h
00003  *
00004  *  Created on: Sep 26, 2012
00005  *      Author: kidson
00006  */
00007 
00008 #ifndef RGB_FEATURE_MATCHER_H_
00009 #define RGB_FEATURE_MATCHER_H_
00010 
00011 #include "rgbd_registration/typedefs.h"
00012 #include <cv.h>
00013 
00014 class RGBFeatureMatcher
00015 {
00016   public:
00017     RGBFeatureMatcher ();
00018 
00019     RGBFeatureMatcher (PointCloudPtr source_cloud_ptr, PointCloudPtr target_cloud_ptr);
00020 
00021     RGBFeatureMatcher (PointCloudPtr source_cloud_ptr, PointCloudPtr target_cloud_ptr,
00022         const cv::Mat& source_image, const cv::Mat& target_image);
00023 
00024     virtual ~RGBFeatureMatcher ();
00025 
00026     void setSourceCloud (const PointCloudPtr source_cloud);
00027     PointCloudConstPtr getSourceCloud ();
00028     void setTargetCloud (const PointCloudPtr target_cloud);
00029     PointCloudConstPtr getTargetCloud ();
00030     void setSourceImage (const cv::Mat& source_image);
00031     cv::Mat getSourceImage ();
00032     void setTargetImage (const cv::Mat& target_image);
00033     cv::Mat getTargetImage ();
00034 
00035     cv::Mat restoreCVMatFromPointCloud (PointCloudConstPtr cloud_in);
00036 
00037     void findMatches (const cv::Mat& source_descriptors, const cv::Mat& target_descriptors,
00038         std::vector<cv::DMatch>& matches);
00039 
00040     void OutlierRemoval (const std::vector<cv::DMatch>& matches,
00041         std::vector<cv::DMatch>& good_matches);
00042 
00043     bool
00044         getMatches (
00045             std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >& source_inlier_3d_locations,
00046             std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >& target_inlier_3d_locations,
00047             Eigen::Matrix4f& ransac_trafo);
00048 
00049   private:
00050     PointCloudConstPtr source_cloud_ptr_, target_cloud_ptr_;
00051     cv::Mat source_image_, target_image_;
00052 };
00053 
00054 #endif /* RGB_FEATURE_MATCHER_H_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


rgbd_registration
Author(s): Ross Kidson
autogenerated on Sun Oct 6 2013 12:00:40