EpipolarGeometry.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #pragma once
29 
30 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
32 #include <opencv2/core/core.hpp>
33 #include <opencv2/features2d/features2d.hpp>
34 #include <pcl/point_cloud.h>
35 #include <pcl/point_types.h>
36 #include <list>
37 #include <vector>
38 
39 namespace rtabmap
40 {
41 
42 class Signature;
43 
45 {
46 public:
47  EpipolarGeometry(const ParametersMap & parameters = ParametersMap());
48  virtual ~EpipolarGeometry();
49  bool check(const Signature * ssA, const Signature * ssB);
50  void parseParameters(const ParametersMap & parameters);
51 
52  int getMatchCountMinAccepted() const {return _matchCountMinAccepted;}
53  double getRansacParam1() const {return _ransacParam1;}
54  double getRansacParam2() const {return _ransacParam2;}
55 
56  void setMatchCountMinAccepted(int matchCountMinAccepted) {_matchCountMinAccepted = matchCountMinAccepted;}
57  void setRansacParam1(double ransacParam1) {_ransacParam1 = ransacParam1;}
58  void setRansacParam2(double ransacParam2) {_ransacParam2 = ransacParam2;}
59 
60 
61  // STATIC STUFF
62  //epipolar geometry
63  static void findEpipolesFromF(
64  const cv::Mat & fundamentalMatrix,
65  cv::Vec3d & e1,
66  cv::Vec3d & e2);
67 
68  static cv::Mat findPFromE(
69  const cv::Mat & E,
70  const cv::Mat & x,
71  const cv::Mat & xp);
72 
73  // return fundamental matrix
74  // status -> inliers = 1, outliers = 0
75  static cv::Mat findFFromWords(
76  const std::list<std::pair<int, std::pair<cv::KeyPoint, cv::KeyPoint> > > & pairs, // id, kpt1, kpt2
77  std::vector<uchar> & status,
78  double ransacParam1 = 3.0,
79  double ransacParam2 = 0.99);
80 
81  // assume a canonical camera (without K)
82  static void findRTFromP(
83  const cv::Mat & p,
84  cv::Mat & r,
85  cv::Mat & t);
86 
87  static cv::Mat findFFromCalibratedStereoCameras(double fx, double fy, double cx, double cy, double Tx, double Ty);
88 
89 
94  static int findPairs(
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);
99 
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);
109 
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);
119 
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);
129 
130  static cv::Mat linearLSTriangulation(
131  cv::Point3d u, //homogenous image point (u,v,1)
132  cv::Matx34d P, //camera 1 matrix 3x4 double
133  cv::Point3d u1, //homogenous image point in 2nd camera
134  cv::Matx34d P1); //camera 2 matrix 3x4 double
135 
136  static cv::Mat iterativeLinearLSTriangulation(
137  cv::Point3d u, //homogenous image point (u,v,1)
138  const cv::Matx34d & P, //camera 1 matrix 3x4 double
139  cv::Point3d u1, //homogenous image point in 2nd camera
140  const cv::Matx34d & P1); //camera 2 matrix 3x4 double
141 
142  static double triangulatePoints(
143  const cv::Mat& pt_set1, //2xN double
144  const cv::Mat& pt_set2, //2xN double
145  const cv::Mat& P, // 3x4 double
146  const cv::Mat& P1, // 3x4 double
147  pcl::PointCloud<pcl::PointXYZ>::Ptr & pointcloud,
148  std::vector<double> & reproj_errors);
149 
150 private:
154 };
155 
156 } // namespace rtabmap
void setRansacParam2(double ransacParam2)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
double getRansacParam1() const
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
void setMatchCountMinAccepted(int matchCountMinAccepted)
double getRansacParam2() const
int getMatchCountMinAccepted() const
void setRansacParam1(double ransacParam1)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31