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 #pragma once
00029
00030 #include "rtabmap/core/RtabmapExp.h"
00031 #include "rtabmap/core/Parameters.h"
00032 #include <opencv2/core/core.hpp>
00033 #include <opencv2/features2d/features2d.hpp>
00034 #include <pcl/point_cloud.h>
00035 #include <pcl/point_types.h>
00036 #include <list>
00037 #include <vector>
00038
00039 namespace rtabmap
00040 {
00041
00042 class Signature;
00043
00044 class RTABMAP_EXP EpipolarGeometry
00045 {
00046 public:
00047 EpipolarGeometry(const ParametersMap & parameters = ParametersMap());
00048 virtual ~EpipolarGeometry();
00049 bool check(const Signature * ssA, const Signature * ssB);
00050 void parseParameters(const ParametersMap & parameters);
00051
00052 int getMatchCountMinAccepted() const {return _matchCountMinAccepted;}
00053 double getRansacParam1() const {return _ransacParam1;}
00054 double getRansacParam2() const {return _ransacParam2;}
00055
00056 void setMatchCountMinAccepted(int matchCountMinAccepted) {_matchCountMinAccepted = matchCountMinAccepted;}
00057 void setRansacParam1(double ransacParam1) {_ransacParam1 = ransacParam1;}
00058 void setRansacParam2(double ransacParam2) {_ransacParam2 = ransacParam2;}
00059
00060
00061
00062
00063 static void findEpipolesFromF(
00064 const cv::Mat & fundamentalMatrix,
00065 cv::Vec3d & e1,
00066 cv::Vec3d & e2);
00067
00068 static cv::Mat findPFromE(
00069 const cv::Mat & E,
00070 const cv::Mat & x,
00071 const cv::Mat & xp);
00072
00073
00074
00075 static cv::Mat findFFromWords(
00076 const std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
00077 std::vector<uchar> & status,
00078 double ransacParam1 = 3.0,
00079 double ransacParam2 = 0.99);
00080
00081
00082 static void findRTFromP(
00083 const cv::Mat & p,
00084 cv::Mat & r,
00085 cv::Mat & t);
00086
00087 static cv::Mat findFFromCalibratedStereoCameras(double fx, double fy, double cx, double cy, double Tx, double Ty);
00088
00089
00094 static int findPairs(
00095 const std::map<int, cv::KeyPoint> & wordsA,
00096 const std::map<int, cv::KeyPoint> & wordsB,
00097 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs);
00098
00103 static int findPairs(
00104 const std::multimap<int, cv::KeyPoint> & wordsA,
00105 const std::multimap<int, cv::KeyPoint> & wordsB,
00106 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs);
00107
00112 static int findPairsUnique(
00113 const std::multimap<int, cv::KeyPoint> & wordsA,
00114 const std::multimap<int, cv::KeyPoint> & wordsB,
00115 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs);
00116
00121 static int findPairsAll(
00122 const std::multimap<int, cv::KeyPoint> & wordsA,
00123 const std::multimap<int, cv::KeyPoint> & wordsB,
00124 std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs);
00125
00126 static cv::Mat linearLSTriangulation(
00127 cv::Point3d u,
00128 cv::Matx34d P,
00129 cv::Point3d u1,
00130 cv::Matx34d P1);
00131
00132 static cv::Mat iterativeLinearLSTriangulation(
00133 cv::Point3d u,
00134 const cv::Matx34d & P,
00135 cv::Point3d u1,
00136 const cv::Matx34d & P1);
00137
00138 static double triangulatePoints(
00139 const cv::Mat& pt_set1,
00140 const cv::Mat& pt_set2,
00141 const cv::Mat& P,
00142 const cv::Mat& P1,
00143 pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud,
00144 std::vector<double> & reproj_errors);
00145
00146 private:
00147 int _matchCountMinAccepted;
00148 double _ransacParam1;
00149 double _ransacParam2;
00150 };
00151
00152 }