Sim3Solver.cc
Go to the documentation of this file.
1 
22 #include "Sim3Solver.h"
23 
24 #include <vector>
25 #include <cmath>
26 #include <opencv2/core/core.hpp>
27 
28 #include "KeyFrame.h"
29 #include "ORBmatcher.h"
30 
32 
33 namespace ORB_SLAM2
34 {
35 
36 
37 Sim3Solver::Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const vector<MapPoint *> &vpMatched12, const bool bFixScale):
38  mnIterations(0), mnBestInliers(0), mbFixScale(bFixScale)
39 {
40  mpKF1 = pKF1;
41  mpKF2 = pKF2;
42 
43  vector<MapPoint*> vpKeyFrameMP1 = pKF1->GetMapPointMatches();
44 
45  mN1 = vpMatched12.size();
46 
47  mvpMapPoints1.reserve(mN1);
48  mvpMapPoints2.reserve(mN1);
49  mvpMatches12 = vpMatched12;
50  mvnIndices1.reserve(mN1);
51  mvX3Dc1.reserve(mN1);
52  mvX3Dc2.reserve(mN1);
53 
54  cv::Mat Rcw1 = pKF1->GetRotation();
55  cv::Mat tcw1 = pKF1->GetTranslation();
56  cv::Mat Rcw2 = pKF2->GetRotation();
57  cv::Mat tcw2 = pKF2->GetTranslation();
58 
59  mvAllIndices.reserve(mN1);
60 
61  size_t idx=0;
62  for(int i1=0; i1<mN1; i1++)
63  {
64  if(vpMatched12[i1])
65  {
66  MapPoint* pMP1 = vpKeyFrameMP1[i1];
67  MapPoint* pMP2 = vpMatched12[i1];
68 
69  if(!pMP1)
70  continue;
71 
72  if(pMP1->isBad() || pMP2->isBad())
73  continue;
74 
75  int indexKF1 = pMP1->GetIndexInKeyFrame(pKF1);
76  int indexKF2 = pMP2->GetIndexInKeyFrame(pKF2);
77 
78  if(indexKF1<0 || indexKF2<0)
79  continue;
80 
81  const cv::KeyPoint &kp1 = pKF1->mvKeysUn[indexKF1];
82  const cv::KeyPoint &kp2 = pKF2->mvKeysUn[indexKF2];
83 
84  const float sigmaSquare1 = pKF1->mvLevelSigma2[kp1.octave];
85  const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave];
86 
87  mvnMaxError1.push_back(9.210*sigmaSquare1);
88  mvnMaxError2.push_back(9.210*sigmaSquare2);
89 
90  mvpMapPoints1.push_back(pMP1);
91  mvpMapPoints2.push_back(pMP2);
92  mvnIndices1.push_back(i1);
93 
94  cv::Mat X3D1w = pMP1->GetWorldPos();
95  mvX3Dc1.push_back(Rcw1*X3D1w+tcw1);
96 
97  cv::Mat X3D2w = pMP2->GetWorldPos();
98  mvX3Dc2.push_back(Rcw2*X3D2w+tcw2);
99 
100  mvAllIndices.push_back(idx);
101  idx++;
102  }
103  }
104 
105  mK1 = pKF1->mK;
106  mK2 = pKF2->mK;
107 
110 
112 }
113 
114 void Sim3Solver::SetRansacParameters(double probability, int minInliers, int maxIterations)
115 {
116  mRansacProb = probability;
117  mRansacMinInliers = minInliers;
118  mRansacMaxIts = maxIterations;
119 
120  N = mvpMapPoints1.size(); // number of correspondences
121 
122  mvbInliersi.resize(N);
123 
124  // Adjust Parameters according to number of correspondences
125  float epsilon = (float)mRansacMinInliers/N;
126 
127  // Set RANSAC iterations according to probability, epsilon, and max iterations
128  int nIterations;
129 
130  if(mRansacMinInliers==N)
131  nIterations=1;
132  else
133  nIterations = ceil(log(1-mRansacProb)/log(1-pow(epsilon,3)));
134 
135  mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts));
136 
137  mnIterations = 0;
138 }
139 
140 cv::Mat Sim3Solver::iterate(int nIterations, bool &bNoMore, vector<bool> &vbInliers, int &nInliers)
141 {
142  bNoMore = false;
143  vbInliers = vector<bool>(mN1,false);
144  nInliers=0;
145 
146  if(N<mRansacMinInliers)
147  {
148  bNoMore = true;
149  return cv::Mat();
150  }
151 
152  vector<size_t> vAvailableIndices;
153 
154  cv::Mat P3Dc1i(3,3,CV_32F);
155  cv::Mat P3Dc2i(3,3,CV_32F);
156 
157  int nCurrentIterations = 0;
158  while(mnIterations<mRansacMaxIts && nCurrentIterations<nIterations)
159  {
160  nCurrentIterations++;
161  mnIterations++;
162 
163  vAvailableIndices = mvAllIndices;
164 
165  // Get min set of points
166  for(short i = 0; i < 3; ++i)
167  {
168  int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1);
169 
170  int idx = vAvailableIndices[randi];
171 
172  mvX3Dc1[idx].copyTo(P3Dc1i.col(i));
173  mvX3Dc2[idx].copyTo(P3Dc2i.col(i));
174 
175  vAvailableIndices[randi] = vAvailableIndices.back();
176  vAvailableIndices.pop_back();
177  }
178 
179  ComputeSim3(P3Dc1i,P3Dc2i);
180 
181  CheckInliers();
182 
184  {
187  mBestT12 = mT12i.clone();
188  mBestRotation = mR12i.clone();
189  mBestTranslation = mt12i.clone();
190  mBestScale = ms12i;
191 
193  {
194  nInliers = mnInliersi;
195  for(int i=0; i<N; i++)
196  if(mvbInliersi[i])
197  vbInliers[mvnIndices1[i]] = true;
198  return mBestT12;
199  }
200  }
201  }
202 
204  bNoMore=true;
205 
206  return cv::Mat();
207 }
208 
209 cv::Mat Sim3Solver::find(vector<bool> &vbInliers12, int &nInliers)
210 {
211  bool bFlag;
212  return iterate(mRansacMaxIts,bFlag,vbInliers12,nInliers);
213 }
214 
215 void Sim3Solver::ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C)
216 {
217  cv::reduce(P,C,1,CV_REDUCE_SUM);
218  C = C/P.cols;
219 
220  for(int i=0; i<P.cols; i++)
221  {
222  Pr.col(i)=P.col(i)-C;
223  }
224 }
225 
226 void Sim3Solver::ComputeSim3(cv::Mat &P1, cv::Mat &P2)
227 {
228  // Custom implementation of:
229  // Horn 1987, Closed-form solution of absolute orientataion using unit quaternions
230 
231  // Step 1: Centroid and relative coordinates
232 
233  cv::Mat Pr1(P1.size(),P1.type()); // Relative coordinates to centroid (set 1)
234  cv::Mat Pr2(P2.size(),P2.type()); // Relative coordinates to centroid (set 2)
235  cv::Mat O1(3,1,Pr1.type()); // Centroid of P1
236  cv::Mat O2(3,1,Pr2.type()); // Centroid of P2
237 
238  ComputeCentroid(P1,Pr1,O1);
239  ComputeCentroid(P2,Pr2,O2);
240 
241  // Step 2: Compute M matrix
242 
243  cv::Mat M = Pr2*Pr1.t();
244 
245  // Step 3: Compute N matrix
246 
247  double N11, N12, N13, N14, N22, N23, N24, N33, N34, N44;
248 
249  cv::Mat N(4,4,P1.type());
250 
251  N11 = M.at<float>(0,0)+M.at<float>(1,1)+M.at<float>(2,2);
252  N12 = M.at<float>(1,2)-M.at<float>(2,1);
253  N13 = M.at<float>(2,0)-M.at<float>(0,2);
254  N14 = M.at<float>(0,1)-M.at<float>(1,0);
255  N22 = M.at<float>(0,0)-M.at<float>(1,1)-M.at<float>(2,2);
256  N23 = M.at<float>(0,1)+M.at<float>(1,0);
257  N24 = M.at<float>(2,0)+M.at<float>(0,2);
258  N33 = -M.at<float>(0,0)+M.at<float>(1,1)-M.at<float>(2,2);
259  N34 = M.at<float>(1,2)+M.at<float>(2,1);
260  N44 = -M.at<float>(0,0)-M.at<float>(1,1)+M.at<float>(2,2);
261 
262  N = (cv::Mat_<float>(4,4) << N11, N12, N13, N14,
263  N12, N22, N23, N24,
264  N13, N23, N33, N34,
265  N14, N24, N34, N44);
266 
267 
268  // Step 4: Eigenvector of the highest eigenvalue
269 
270  cv::Mat eval, evec;
271 
272  cv::eigen(N,eval,evec); //evec[0] is the quaternion of the desired rotation
273 
274  cv::Mat vec(1,3,evec.type());
275  (evec.row(0).colRange(1,4)).copyTo(vec); //extract imaginary part of the quaternion (sin*axis)
276 
277  // Rotation angle. sin is the norm of the imaginary part, cos is the real part
278  double ang=atan2(norm(vec),evec.at<float>(0,0));
279 
280  vec = 2*ang*vec/norm(vec); //Angle-axis representation. quaternion angle is the half
281 
282  mR12i.create(3,3,P1.type());
283 
284  cv::Rodrigues(vec,mR12i); // computes the rotation matrix from angle-axis
285 
286  // Step 5: Rotate set 2
287 
288  cv::Mat P3 = mR12i*Pr2;
289 
290  // Step 6: Scale
291 
292  if(!mbFixScale)
293  {
294  double nom = Pr1.dot(P3);
295  cv::Mat aux_P3(P3.size(),P3.type());
296  aux_P3=P3;
297  cv::pow(P3,2,aux_P3);
298  double den = 0;
299 
300  for(int i=0; i<aux_P3.rows; i++)
301  {
302  for(int j=0; j<aux_P3.cols; j++)
303  {
304  den+=aux_P3.at<float>(i,j);
305  }
306  }
307 
308  ms12i = nom/den;
309  }
310  else
311  ms12i = 1.0f;
312 
313  // Step 7: Translation
314 
315  mt12i.create(1,3,P1.type());
316  mt12i = O1 - ms12i*mR12i*O2;
317 
318  // Step 8: Transformation
319 
320  // Step 8.1 T12
321  mT12i = cv::Mat::eye(4,4,P1.type());
322 
323  cv::Mat sR = ms12i*mR12i;
324 
325  sR.copyTo(mT12i.rowRange(0,3).colRange(0,3));
326  mt12i.copyTo(mT12i.rowRange(0,3).col(3));
327 
328  // Step 8.2 T21
329 
330  mT21i = cv::Mat::eye(4,4,P1.type());
331 
332  cv::Mat sRinv = (1.0/ms12i)*mR12i.t();
333 
334  sRinv.copyTo(mT21i.rowRange(0,3).colRange(0,3));
335  cv::Mat tinv = -sRinv*mt12i;
336  tinv.copyTo(mT21i.rowRange(0,3).col(3));
337 }
338 
339 
341 {
342  vector<cv::Mat> vP1im2, vP2im1;
343  Project(mvX3Dc2,vP2im1,mT12i,mK1);
344  Project(mvX3Dc1,vP1im2,mT21i,mK2);
345 
346  mnInliersi=0;
347 
348  for(size_t i=0; i<mvP1im1.size(); i++)
349  {
350  cv::Mat dist1 = mvP1im1[i]-vP2im1[i];
351  cv::Mat dist2 = vP1im2[i]-mvP2im2[i];
352 
353  const float err1 = dist1.dot(dist1);
354  const float err2 = dist2.dot(dist2);
355 
356  if(err1<mvnMaxError1[i] && err2<mvnMaxError2[i])
357  {
358  mvbInliersi[i]=true;
359  mnInliersi++;
360  }
361  else
362  mvbInliersi[i]=false;
363  }
364 }
365 
366 
368 {
369  return mBestRotation.clone();
370 }
371 
373 {
374  return mBestTranslation.clone();
375 }
376 
378 {
379  return mBestScale;
380 }
381 
382 void Sim3Solver::Project(const vector<cv::Mat> &vP3Dw, vector<cv::Mat> &vP2D, cv::Mat Tcw, cv::Mat K)
383 {
384  cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3);
385  cv::Mat tcw = Tcw.rowRange(0,3).col(3);
386  const float &fx = K.at<float>(0,0);
387  const float &fy = K.at<float>(1,1);
388  const float &cx = K.at<float>(0,2);
389  const float &cy = K.at<float>(1,2);
390 
391  vP2D.clear();
392  vP2D.reserve(vP3Dw.size());
393 
394  for(size_t i=0, iend=vP3Dw.size(); i<iend; i++)
395  {
396  cv::Mat P3Dc = Rcw*vP3Dw[i]+tcw;
397  const float invz = 1/(P3Dc.at<float>(2));
398  const float x = P3Dc.at<float>(0)*invz;
399  const float y = P3Dc.at<float>(1)*invz;
400 
401  vP2D.push_back((cv::Mat_<float>(2,1) << fx*x+cx, fy*y+cy));
402  }
403 }
404 
405 void Sim3Solver::FromCameraToImage(const vector<cv::Mat> &vP3Dc, vector<cv::Mat> &vP2D, cv::Mat K)
406 {
407  const float &fx = K.at<float>(0,0);
408  const float &fy = K.at<float>(1,1);
409  const float &cx = K.at<float>(0,2);
410  const float &cy = K.at<float>(1,2);
411 
412  vP2D.clear();
413  vP2D.reserve(vP3Dc.size());
414 
415  for(size_t i=0, iend=vP3Dc.size(); i<iend; i++)
416  {
417  const float invz = 1/(vP3Dc[i].at<float>(2));
418  const float x = vP3Dc[i].at<float>(0)*invz;
419  const float y = vP3Dc[i].at<float>(1)*invz;
420 
421  vP2D.push_back((cv::Mat_<float>(2,1) << fx*x+cx, fy*y+cy));
422  }
423 }
424 
425 } //namespace ORB_SLAM
cv::Mat GetRotation()
Definition: KeyFrame.cc:111
std::vector< size_t > mvnMaxError2
Definition: Sim3Solver.h:80
std::vector< cv::Mat > mvP2im2
Definition: Sim3Solver.h:111
double epsilon
const std::vector< cv::KeyPoint > mvKeysUn
Definition: KeyFrame.h:165
cv::Mat find(std::vector< bool > &vbInliers12, int &nInliers)
Definition: Sim3Solver.cc:209
std::vector< cv::Mat > mvX3Dc1
Definition: Sim3Solver.h:71
cv::Mat iterate(int nIterations, bool &bNoMore, std::vector< bool > &vbInliers, int &nInliers)
Definition: Sim3Solver.cc:140
void Project(const std::vector< cv::Mat > &vP3Dw, std::vector< cv::Mat > &vP2D, cv::Mat Tcw, cv::Mat K)
Definition: Sim3Solver.cc:382
const std::vector< float > mvLevelSigma2
Definition: KeyFrame.h:182
std::vector< size_t > mvnMaxError1
Definition: Sim3Solver.h:79
cv::Mat GetWorldPos()
Definition: MapPoint.cc:80
std::vector< MapPoint * > GetMapPointMatches()
Definition: KeyFrame.cc:277
void ComputeSim3(cv::Mat &P1, cv::Mat &P2)
Definition: Sim3Solver.cc:226
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< MapPoint * > mvpMatches12
Definition: Sim3Solver.h:75
std::vector< cv::Mat > mvP1im1
Definition: Sim3Solver.h:110
const cv::Mat mK
Definition: KeyFrame.h:190
cv::Mat GetEstimatedRotation()
Definition: Sim3Solver.cc:367
Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const std::vector< MapPoint * > &vpMatched12, const bool bFixScale=true)
Definition: Sim3Solver.cc:37
std::vector< bool > mvbInliersi
Definition: Sim3Solver.h:91
cv::Mat GetTranslation()
Definition: KeyFrame.cc:117
void FromCameraToImage(const std::vector< cv::Mat > &vP3Dc, std::vector< cv::Mat > &vP2D, cv::Mat K)
Definition: Sim3Solver.cc:405
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< MapPoint * > mvpMapPoints2
Definition: Sim3Solver.h:74
static int RandomInt(int min, int max)
Definition: Random.cpp:47
void ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C)
Definition: Sim3Solver.cc:215
void SetRansacParameters(double probability=0.99, int minInliers=6, int maxIterations=300)
Definition: Sim3Solver.cc:114
std::vector< MapPoint * > mvpMapPoints1
Definition: Sim3Solver.h:73
std::vector< cv::Mat > mvX3Dc2
Definition: Sim3Solver.h:72
int min(int a, int b)
std::vector< size_t > mvnIndices1
Definition: Sim3Solver.h:76
int GetIndexInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:315
std::vector< size_t > mvAllIndices
Definition: Sim3Solver.h:107
std::vector< bool > mvbBestInliers
Definition: Sim3Solver.h:96
cv::Mat GetEstimatedTranslation()
Definition: Sim3Solver.cc:372


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:05