esm.hpp
Go to the documentation of this file.
00001 #ifndef ESM_HPP_
00002 #define ESM_HPP_
00003 
00004 #include <posest/MatrixFunctions>
00005 namespace Eigen
00006 {
00007 using namespace Eigen;
00008 }
00009 
00010 #include <opencv2/core/core.hpp>
00011 #include <opencv2/core/eigen.hpp>
00012 #include <opencv2/imgproc/imgproc.hpp>
00013 #include <opencv2/highgui/highgui.hpp>
00014 #include <opencv2/contrib/contrib.hpp>
00015 #include <opencv2/features2d/features2d.hpp>
00016 #include <opencv2/calib3d/calib3d.hpp>
00017 
00018 #include <posest/lie_algebra.hpp>
00019 
00020 struct HomoESMState
00021 {
00022   cv::Mat H;
00023   double error;
00024 };
00025 
00026 class HomoESM
00027 {
00028 public:
00029   void setTemplateImage(const cv::Mat &image);
00030   void setTestImage(const cv::Mat &image);
00031   void track(int nIters, cv::Mat &H, double &rmsError, cv::Ptr<LieAlgebra> lieAlgebra = new LieAlgebraHomography(),
00032              bool saveComputations = false, std::vector<HomoESMState> *computations = 0) const;
00033   void visualizeTracking(const cv::Mat &H, cv::Mat &visualization) const;
00034   void checkAccuracy(std::vector<std::vector<HomoESMState> > &computations, std::string groundTruthFile, double &meanSSDError,
00035                      double &meanSpatialError) const;
00036 private:
00037   cv::Mat testImage;
00038   cv::Mat templateImage, templateImageRowDouble;
00039   cv::Mat templateDxRow, templateDyRow;
00040   cv::Mat templatePoints;
00041   cv::Mat xx, yy;
00042 
00043   std::vector<cv::Point2f> templateVertices;
00044 
00045   static void computeGradient(const cv::Mat &image, cv::Mat &dx, cv::Mat &dy);
00046   static double computeRMSError(const cv::Mat &error);
00047   void computeJacobian(const cv::Mat &dx, const cv::Mat &dy, cv::Mat &J, cv::Ptr<LieAlgebra> lieAlgebra) const;
00048   void constructImage(const cv::Mat &srcImage, const std::vector<cv::Point2f> &points, cv::Mat &intensity) const;
00049   void projectVertices(const cv::Mat &H, std::vector<cv::Point2f> &vertices) const;
00050 };
00051 
00052 #endif /* ESM_HPP_ */


posest
Author(s): Kurt Konolige
autogenerated on Thu Jan 2 2014 12:12:17