32 #include <opencv2/core/core.hpp> 33 #include <opencv2/features2d/features2d.hpp> 34 #include <pcl/point_cloud.h> 35 #include <pcl/point_types.h> 63 static void findEpipolesFromF(
64 const cv::Mat & fundamentalMatrix,
68 static cv::Mat findPFromE(
75 static cv::Mat findFFromWords(
76 const std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
77 std::vector<uchar> & status,
78 double ransacParam1 = 3.0,
79 double ransacParam2 = 0.99);
82 static void findRTFromP(
87 static cv::Mat findFFromCalibratedStereoCameras(
double fx,
double fy,
double cx,
double cy,
double Tx,
double Ty);
95 const std::map<int, cv::KeyPoint> & wordsA,
96 const std::map<int, cv::KeyPoint> & wordsB,
97 std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
98 bool ignoreNegativeIds =
true);
104 static int findPairs(
105 const std::multimap<int, cv::KeyPoint> & wordsA,
106 const std::multimap<int, cv::KeyPoint> & wordsB,
107 std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
108 bool ignoreNegativeIds =
true);
114 static int findPairsUnique(
115 const std::multimap<int, cv::KeyPoint> & wordsA,
116 const std::multimap<int, cv::KeyPoint> & wordsB,
117 std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
118 bool ignoreNegativeIds =
true);
124 static int findPairsAll(
125 const std::multimap<int, cv::KeyPoint> & wordsA,
126 const std::multimap<int, cv::KeyPoint> & wordsB,
127 std::list<std::pair<
int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs,
128 bool ignoreNegativeIds =
true);
130 static cv::Mat linearLSTriangulation(
136 static cv::Mat iterativeLinearLSTriangulation(
138 const cv::Matx34d & P,
140 const cv::Matx34d & P1);
142 static double triangulatePoints(
143 const cv::Mat& pt_set1,
144 const cv::Mat& pt_set2,
147 pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud,
148 std::vector<double> & reproj_errors);
void setRansacParam2(double ransacParam2)
std::map< std::string, std::string > ParametersMap
int _matchCountMinAccepted
double getRansacParam1() const
void setMatchCountMinAccepted(int matchCountMinAccepted)
double getRansacParam2() const
int getMatchCountMinAccepted() const
void setRansacParam1(double ransacParam1)