Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef _PE_H_
00037 #define _PE_H_
00038
00039 #include <frame_common/frame.h>
00040 #include <boost/shared_ptr.hpp>
00041 #include <cv.h>
00042 #include <cstdlib>
00043 #include <math.h>
00044
00045 namespace fc = frame_common;
00046
00047 namespace pe
00048 {
00050 class PoseEstimator
00051 {
00052 public:
00053 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00054
00055 enum MethodType
00056 {
00057 SFM = 0,
00058 PnP = 1,
00059 Stereo = 2
00060 };
00061
00062 MethodType usedMethod;
00063
00064
00065 bool polish;
00066
00067
00068 std::vector<cv::DMatch> matches;
00069 std::vector<cv::DMatch> inliers;
00070
00072 int numRansac;
00073
00075 int windowed;
00076
00078 cv::Ptr<cv::DescriptorMatcher> matcher;
00079 int wx , wy ;
00080
00081 PoseEstimator(int NRansac, bool LMpolish, double mind,
00082 double maxidx, double maxidd);
00083 ~PoseEstimator() { }
00084
00086 double minMatchDisp;
00087
00089 double maxInlierXDist2, maxInlierDDist2;
00090
00092 void setMatcher(const cv::Ptr<cv::DescriptorMatcher>& matcher);
00093
00097 virtual int estimate(const fc::Frame& frame1, const fc::Frame& frame2,
00098 const std::vector<cv::DMatch> &matches) = 0;
00099
00103 virtual int estimate(const fc::Frame& frame1, const fc::Frame& frame2);
00104
00105
00106
00107
00108 void setTestMode(bool mode);
00109 void setTestMatches(const std::vector<cv::DMatch>& matches)
00110 {
00111 assert(testMode==true);
00112 testMatches = matches;
00113 };
00114
00116 MethodType getMethod() const {return usedMethod;};
00117
00118
00119 Eigen::Matrix3d rot;
00120 Eigen::Vector3d trans;
00121
00122 protected:
00123 void matchFrames(const fc::Frame& f0, const fc::Frame& f1, std::vector<cv::DMatch>& fwd_matches);
00124
00125 bool testMode;
00126 std::vector<cv::DMatch> testMatches;
00127
00128 };
00129
00130
00131
00132 }
00133 #endif // _PE3D_H_