ransac_transformation.h
Go to the documentation of this file.
00001 /*
00002  * RansacTransformation.h
00003  *
00004  *  Created on: 13.07.2012
00005  *      Author: ross
00006  */
00007 
00008 #ifndef RANSACTRANSFORMATION_H_
00009 #define RANSACTRANSFORMATION_H_
00010 
00011 //opencv
00012 #include <opencv/cv.h>
00013 
00014 #include <Eigen/Core>
00015 
00016 class RansacTransformation
00017 {
00018   public:
00019     RansacTransformation ();
00020     virtual ~RansacTransformation ();
00021 
00022     template<class InputIterator>
00023     Eigen::Matrix4f
00024         getTransformFromMatches (const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<
00025             Eigen::Vector4f> > & source_feature_locations_3d, const std::vector<Eigen::Vector4f,
00026             Eigen::aligned_allocator<Eigen::Vector4f> > & target_feature_locations_3d,
00027             InputIterator iter_begin, InputIterator iter_end, bool& valid, float max_dist_m);
00028 
00029     void computeInliersAndError (
00030         const std::vector<cv::DMatch>& matches,
00031         const Eigen::Matrix4f& transformation,
00032         const std::vector<Eigen::Vector4f,Eigen::aligned_allocator<Eigen::Vector4f> >& origins,
00033         const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> >& earlier,
00034         std::vector<cv::DMatch>& inliers, //output var
00035         double& mean_error, std::vector<double>& errors, double squaredMaxInlierDistInM);
00036 
00037     bool
00038     getRelativeTransformationTo (const std::vector<Eigen::Vector4f, Eigen::aligned_allocator<
00039         Eigen::Vector4f> > & source_feature_locations_3d, const std::vector<Eigen::Vector4f,
00040         Eigen::aligned_allocator<Eigen::Vector4f> > & target_feature_locations_3d, std::vector<
00041         cv::DMatch>* initial_matches, Eigen::Matrix4f& resulting_transformation, float& rmse,
00042         std::vector<cv::DMatch>& matches, uint min_matches);
00043 };
00044 
00045 #endif /* RANSACTRANSFORMATION_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