Optimizer.cc
Go to the documentation of this file.
1 
21 #include "Optimizer.h"
22 
30 
31 #include<Eigen/StdVector>
32 
33 #include "Converter.h"
34 
35 #include<mutex>
36 
37 namespace ORB_SLAM2
38 {
39 
40 
41 void Optimizer::GlobalBundleAdjustemnt(Map* pMap, int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust)
42 {
43  vector<KeyFrame*> vpKFs = pMap->GetAllKeyFrames();
44  vector<MapPoint*> vpMP = pMap->GetAllMapPoints();
45  BundleAdjustment(vpKFs,vpMP,nIterations,pbStopFlag, nLoopKF, bRobust);
46 }
47 
48 
49 void Optimizer::BundleAdjustment(const vector<KeyFrame *> &vpKFs, const vector<MapPoint *> &vpMP,
50  int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust)
51 {
52  vector<bool> vbNotIncludedMP;
53  vbNotIncludedMP.resize(vpMP.size());
54 
55  g2o::SparseOptimizer optimizer;
57 
59 
60  g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver);
61 
63  optimizer.setAlgorithm(solver);
64 
65  if(pbStopFlag)
66  optimizer.setForceStopFlag(pbStopFlag);
67 
68  long unsigned int maxKFid = 0;
69 
70  // Set KeyFrame vertices
71  for(size_t i=0; i<vpKFs.size(); i++)
72  {
73  KeyFrame* pKF = vpKFs[i];
74  if(pKF->isBad())
75  continue;
78  vSE3->setId(pKF->mnId);
79  vSE3->setFixed(pKF->mnId==0);
80  optimizer.addVertex(vSE3);
81  if(pKF->mnId>maxKFid)
82  maxKFid=pKF->mnId;
83  }
84 
85  const float thHuber2D = sqrt(5.99);
86  const float thHuber3D = sqrt(7.815);
87 
88  // Set MapPoint vertices
89  for(size_t i=0; i<vpMP.size(); i++)
90  {
91  MapPoint* pMP = vpMP[i];
92  if(pMP->isBad())
93  continue;
96  const int id = pMP->mnId+maxKFid+1;
97  vPoint->setId(id);
98  vPoint->setMarginalized(true);
99  optimizer.addVertex(vPoint);
100 
101  const map<KeyFrame*,size_t> observations = pMP->GetObservations();
102 
103  int nEdges = 0;
104  //SET EDGES
105  for(map<KeyFrame*,size_t>::const_iterator mit=observations.begin(); mit!=observations.end(); mit++)
106  {
107 
108  KeyFrame* pKF = mit->first;
109  if(pKF->isBad() || pKF->mnId>maxKFid)
110  continue;
111 
112  nEdges++;
113 
114  const cv::KeyPoint &kpUn = pKF->mvKeysUn[mit->second];
115 
116  if(pKF->mvuRight[mit->second]<0)
117  {
118  Eigen::Matrix<double,2,1> obs;
119  obs << kpUn.pt.x, kpUn.pt.y;
120 
122 
123  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id)));
124  e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pKF->mnId)));
125  e->setMeasurement(obs);
126  const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave];
127  e->setInformation(Eigen::Matrix2d::Identity()*invSigma2);
128 
129  if(bRobust)
130  {
132  e->setRobustKernel(rk);
133  rk->setDelta(thHuber2D);
134  }
135 
136  e->fx = pKF->fx;
137  e->fy = pKF->fy;
138  e->cx = pKF->cx;
139  e->cy = pKF->cy;
140 
141  optimizer.addEdge(e);
142  }
143  else
144  {
145  Eigen::Matrix<double,3,1> obs;
146  const float kp_ur = pKF->mvuRight[mit->second];
147  obs << kpUn.pt.x, kpUn.pt.y, kp_ur;
148 
150 
151  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id)));
152  e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pKF->mnId)));
153  e->setMeasurement(obs);
154  const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave];
155  Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2;
156  e->setInformation(Info);
157 
158  if(bRobust)
159  {
161  e->setRobustKernel(rk);
162  rk->setDelta(thHuber3D);
163  }
164 
165  e->fx = pKF->fx;
166  e->fy = pKF->fy;
167  e->cx = pKF->cx;
168  e->cy = pKF->cy;
169  e->bf = pKF->mbf;
170 
171  optimizer.addEdge(e);
172  }
173  }
174 
175  if(nEdges==0)
176  {
177  optimizer.removeVertex(vPoint);
178  vbNotIncludedMP[i]=true;
179  }
180  else
181  {
182  vbNotIncludedMP[i]=false;
183  }
184  }
185 
186  // Optimize!
187  optimizer.initializeOptimization();
188  optimizer.optimize(nIterations);
189 
190  // Recover optimized data
191 
192  //Keyframes
193  for(size_t i=0; i<vpKFs.size(); i++)
194  {
195  KeyFrame* pKF = vpKFs[i];
196  if(pKF->isBad())
197  continue;
198  g2o::VertexSE3Expmap* vSE3 = static_cast<g2o::VertexSE3Expmap*>(optimizer.vertex(pKF->mnId));
199  g2o::SE3Quat SE3quat = vSE3->estimate();
200  if(nLoopKF==0)
201  {
202  pKF->SetPose(Converter::toCvMat(SE3quat));
203  }
204  else
205  {
206  pKF->mTcwGBA.create(4,4,CV_32F);
207  Converter::toCvMat(SE3quat).copyTo(pKF->mTcwGBA);
208  pKF->mnBAGlobalForKF = nLoopKF;
209  }
210  }
211 
212  //Points
213  for(size_t i=0; i<vpMP.size(); i++)
214  {
215  if(vbNotIncludedMP[i])
216  continue;
217 
218  MapPoint* pMP = vpMP[i];
219 
220  if(pMP->isBad())
221  continue;
222  g2o::VertexSBAPointXYZ* vPoint = static_cast<g2o::VertexSBAPointXYZ*>(optimizer.vertex(pMP->mnId+maxKFid+1));
223 
224  if(nLoopKF==0)
225  {
226  pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate()));
227  pMP->UpdateNormalAndDepth();
228  }
229  else
230  {
231  pMP->mPosGBA.create(3,1,CV_32F);
232  Converter::toCvMat(vPoint->estimate()).copyTo(pMP->mPosGBA);
233  pMP->mnBAGlobalForKF = nLoopKF;
234  }
235  }
236 
237 }
238 
240 {
241  g2o::SparseOptimizer optimizer;
243 
245 
246  g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver);
247 
249  optimizer.setAlgorithm(solver);
250 
251  int nInitialCorrespondences=0;
252 
253  // Set Frame vertex
255  vSE3->setEstimate(Converter::toSE3Quat(pFrame->mTcw));
256  vSE3->setId(0);
257  vSE3->setFixed(false);
258  optimizer.addVertex(vSE3);
259 
260  // Set MapPoint vertices
261  const int N = pFrame->N;
262 
263  vector<g2o::EdgeSE3ProjectXYZOnlyPose*> vpEdgesMono;
264  vector<size_t> vnIndexEdgeMono;
265  vpEdgesMono.reserve(N);
266  vnIndexEdgeMono.reserve(N);
267 
268  vector<g2o::EdgeStereoSE3ProjectXYZOnlyPose*> vpEdgesStereo;
269  vector<size_t> vnIndexEdgeStereo;
270  vpEdgesStereo.reserve(N);
271  vnIndexEdgeStereo.reserve(N);
272 
273  const float deltaMono = sqrt(5.991);
274  const float deltaStereo = sqrt(7.815);
275 
276 
277  {
278  unique_lock<mutex> lock(MapPoint::mGlobalMutex);
279 
280  for(int i=0; i<N; i++)
281  {
282  MapPoint* pMP = pFrame->mvpMapPoints[i];
283  if(pMP)
284  {
285  // Monocular observation
286  if(pFrame->mvuRight[i]<0)
287  {
288  nInitialCorrespondences++;
289  pFrame->mvbOutlier[i] = false;
290 
291  Eigen::Matrix<double,2,1> obs;
292  const cv::KeyPoint &kpUn = pFrame->mvKeysUn[i];
293  obs << kpUn.pt.x, kpUn.pt.y;
294 
296 
297  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(0)));
298  e->setMeasurement(obs);
299  const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave];
300  e->setInformation(Eigen::Matrix2d::Identity()*invSigma2);
301 
303  e->setRobustKernel(rk);
304  rk->setDelta(deltaMono);
305 
306  e->fx = pFrame->fx;
307  e->fy = pFrame->fy;
308  e->cx = pFrame->cx;
309  e->cy = pFrame->cy;
310  cv::Mat Xw = pMP->GetWorldPos();
311  e->Xw[0] = Xw.at<float>(0);
312  e->Xw[1] = Xw.at<float>(1);
313  e->Xw[2] = Xw.at<float>(2);
314 
315  optimizer.addEdge(e);
316 
317  vpEdgesMono.push_back(e);
318  vnIndexEdgeMono.push_back(i);
319  }
320  else // Stereo observation
321  {
322  nInitialCorrespondences++;
323  pFrame->mvbOutlier[i] = false;
324 
325  //SET EDGE
326  Eigen::Matrix<double,3,1> obs;
327  const cv::KeyPoint &kpUn = pFrame->mvKeysUn[i];
328  const float &kp_ur = pFrame->mvuRight[i];
329  obs << kpUn.pt.x, kpUn.pt.y, kp_ur;
330 
332 
333  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(0)));
334  e->setMeasurement(obs);
335  const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave];
336  Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2;
337  e->setInformation(Info);
338 
340  e->setRobustKernel(rk);
341  rk->setDelta(deltaStereo);
342 
343  e->fx = pFrame->fx;
344  e->fy = pFrame->fy;
345  e->cx = pFrame->cx;
346  e->cy = pFrame->cy;
347  e->bf = pFrame->mbf;
348  cv::Mat Xw = pMP->GetWorldPos();
349  e->Xw[0] = Xw.at<float>(0);
350  e->Xw[1] = Xw.at<float>(1);
351  e->Xw[2] = Xw.at<float>(2);
352 
353  optimizer.addEdge(e);
354 
355  vpEdgesStereo.push_back(e);
356  vnIndexEdgeStereo.push_back(i);
357  }
358  }
359 
360  }
361  }
362 
363 
364  if(nInitialCorrespondences<3)
365  return 0;
366 
367  // We perform 4 optimizations, after each optimization we classify observation as inlier/outlier
368  // At the next optimization, outliers are not included, but at the end they can be classified as inliers again.
369  const float chi2Mono[4]={5.991,5.991,5.991,5.991};
370  const float chi2Stereo[4]={7.815,7.815,7.815, 7.815};
371  const int its[4]={10,10,10,10};
372 
373  int nBad=0;
374  for(size_t it=0; it<4; it++)
375  {
376 
377  vSE3->setEstimate(Converter::toSE3Quat(pFrame->mTcw));
378  optimizer.initializeOptimization(0);
379  optimizer.optimize(its[it]);
380 
381  nBad=0;
382  for(size_t i=0, iend=vpEdgesMono.size(); i<iend; i++)
383  {
384  g2o::EdgeSE3ProjectXYZOnlyPose* e = vpEdgesMono[i];
385 
386  const size_t idx = vnIndexEdgeMono[i];
387 
388  if(pFrame->mvbOutlier[idx])
389  {
390  e->computeError();
391  }
392 
393  const float chi2 = e->chi2();
394 
395  if(chi2>chi2Mono[it])
396  {
397  pFrame->mvbOutlier[idx]=true;
398  e->setLevel(1);
399  nBad++;
400  }
401  else
402  {
403  pFrame->mvbOutlier[idx]=false;
404  e->setLevel(0);
405  }
406 
407  if(it==2)
408  e->setRobustKernel(0);
409  }
410 
411  for(size_t i=0, iend=vpEdgesStereo.size(); i<iend; i++)
412  {
413  g2o::EdgeStereoSE3ProjectXYZOnlyPose* e = vpEdgesStereo[i];
414 
415  const size_t idx = vnIndexEdgeStereo[i];
416 
417  if(pFrame->mvbOutlier[idx])
418  {
419  e->computeError();
420  }
421 
422  const float chi2 = e->chi2();
423 
424  if(chi2>chi2Stereo[it])
425  {
426  pFrame->mvbOutlier[idx]=true;
427  e->setLevel(1);
428  nBad++;
429  }
430  else
431  {
432  e->setLevel(0);
433  pFrame->mvbOutlier[idx]=false;
434  }
435 
436  if(it==2)
437  e->setRobustKernel(0);
438  }
439 
440  if(optimizer.edges().size()<10)
441  break;
442  }
443 
444  // Recover optimized pose and return number of inliers
445  g2o::VertexSE3Expmap* vSE3_recov = static_cast<g2o::VertexSE3Expmap*>(optimizer.vertex(0));
446  g2o::SE3Quat SE3quat_recov = vSE3_recov->estimate();
447  cv::Mat pose = Converter::toCvMat(SE3quat_recov);
448  pFrame->SetPose(pose);
449 
450  return nInitialCorrespondences-nBad;
451 }
452 
453 void Optimizer::LocalBundleAdjustment(KeyFrame *pKF, bool* pbStopFlag, Map* pMap)
454 {
455  // Local KeyFrames: First Breath Search from Current Keyframe
456  list<KeyFrame*> lLocalKeyFrames;
457 
458  lLocalKeyFrames.push_back(pKF);
459  pKF->mnBALocalForKF = pKF->mnId;
460 
461  const vector<KeyFrame*> vNeighKFs = pKF->GetVectorCovisibleKeyFrames();
462  for(int i=0, iend=vNeighKFs.size(); i<iend; i++)
463  {
464  KeyFrame* pKFi = vNeighKFs[i];
465  pKFi->mnBALocalForKF = pKF->mnId;
466  if(!pKFi->isBad())
467  lLocalKeyFrames.push_back(pKFi);
468  }
469 
470  // Local MapPoints seen in Local KeyFrames
471  list<MapPoint*> lLocalMapPoints;
472  for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin() , lend=lLocalKeyFrames.end(); lit!=lend; lit++)
473  {
474  vector<MapPoint*> vpMPs = (*lit)->GetMapPointMatches();
475  for(vector<MapPoint*>::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++)
476  {
477  MapPoint* pMP = *vit;
478  if(pMP)
479  if(!pMP->isBad())
480  if(pMP->mnBALocalForKF!=pKF->mnId)
481  {
482  lLocalMapPoints.push_back(pMP);
483  pMP->mnBALocalForKF=pKF->mnId;
484  }
485  }
486  }
487 
488  // Fixed Keyframes. Keyframes that see Local MapPoints but that are not Local Keyframes
489  list<KeyFrame*> lFixedCameras;
490  for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
491  {
492  map<KeyFrame*,size_t> observations = (*lit)->GetObservations();
493  for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
494  {
495  KeyFrame* pKFi = mit->first;
496 
497  if(pKFi->mnBALocalForKF!=pKF->mnId && pKFi->mnBAFixedForKF!=pKF->mnId)
498  {
499  pKFi->mnBAFixedForKF=pKF->mnId;
500  if(!pKFi->isBad())
501  lFixedCameras.push_back(pKFi);
502  }
503  }
504  }
505 
506  // Setup optimizer
507  g2o::SparseOptimizer optimizer;
509 
511 
512  g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver);
513 
515  optimizer.setAlgorithm(solver);
516 
517  if(pbStopFlag)
518  optimizer.setForceStopFlag(pbStopFlag);
519 
520  unsigned long maxKFid = 0;
521 
522  // Set Local KeyFrame vertices
523  for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++)
524  {
525  KeyFrame* pKFi = *lit;
527  vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose()));
528  vSE3->setId(pKFi->mnId);
529  vSE3->setFixed(pKFi->mnId==0);
530  optimizer.addVertex(vSE3);
531  if(pKFi->mnId>maxKFid)
532  maxKFid=pKFi->mnId;
533  }
534 
535  // Set Fixed KeyFrame vertices
536  for(list<KeyFrame*>::iterator lit=lFixedCameras.begin(), lend=lFixedCameras.end(); lit!=lend; lit++)
537  {
538  KeyFrame* pKFi = *lit;
540  vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose()));
541  vSE3->setId(pKFi->mnId);
542  vSE3->setFixed(true);
543  optimizer.addVertex(vSE3);
544  if(pKFi->mnId>maxKFid)
545  maxKFid=pKFi->mnId;
546  }
547 
548  // Set MapPoint vertices
549  const int nExpectedSize = (lLocalKeyFrames.size()+lFixedCameras.size())*lLocalMapPoints.size();
550 
551  vector<g2o::EdgeSE3ProjectXYZ*> vpEdgesMono;
552  vpEdgesMono.reserve(nExpectedSize);
553 
554  vector<KeyFrame*> vpEdgeKFMono;
555  vpEdgeKFMono.reserve(nExpectedSize);
556 
557  vector<MapPoint*> vpMapPointEdgeMono;
558  vpMapPointEdgeMono.reserve(nExpectedSize);
559 
560  vector<g2o::EdgeStereoSE3ProjectXYZ*> vpEdgesStereo;
561  vpEdgesStereo.reserve(nExpectedSize);
562 
563  vector<KeyFrame*> vpEdgeKFStereo;
564  vpEdgeKFStereo.reserve(nExpectedSize);
565 
566  vector<MapPoint*> vpMapPointEdgeStereo;
567  vpMapPointEdgeStereo.reserve(nExpectedSize);
568 
569  const float thHuberMono = sqrt(5.991);
570  const float thHuberStereo = sqrt(7.815);
571 
572  for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
573  {
574  MapPoint* pMP = *lit;
577  int id = pMP->mnId+maxKFid+1;
578  vPoint->setId(id);
579  vPoint->setMarginalized(true);
580  optimizer.addVertex(vPoint);
581 
582  const map<KeyFrame*,size_t> observations = pMP->GetObservations();
583 
584  //Set edges
585  for(map<KeyFrame*,size_t>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
586  {
587  KeyFrame* pKFi = mit->first;
588 
589  if(!pKFi->isBad())
590  {
591  const cv::KeyPoint &kpUn = pKFi->mvKeysUn[mit->second];
592 
593  // Monocular observation
594  if(pKFi->mvuRight[mit->second]<0)
595  {
596  Eigen::Matrix<double,2,1> obs;
597  obs << kpUn.pt.x, kpUn.pt.y;
598 
600 
601  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id)));
602  e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pKFi->mnId)));
603  e->setMeasurement(obs);
604  const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave];
605  e->setInformation(Eigen::Matrix2d::Identity()*invSigma2);
606 
608  e->setRobustKernel(rk);
609  rk->setDelta(thHuberMono);
610 
611  e->fx = pKFi->fx;
612  e->fy = pKFi->fy;
613  e->cx = pKFi->cx;
614  e->cy = pKFi->cy;
615 
616  optimizer.addEdge(e);
617  vpEdgesMono.push_back(e);
618  vpEdgeKFMono.push_back(pKFi);
619  vpMapPointEdgeMono.push_back(pMP);
620  }
621  else // Stereo observation
622  {
623  Eigen::Matrix<double,3,1> obs;
624  const float kp_ur = pKFi->mvuRight[mit->second];
625  obs << kpUn.pt.x, kpUn.pt.y, kp_ur;
626 
628 
629  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id)));
630  e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pKFi->mnId)));
631  e->setMeasurement(obs);
632  const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave];
633  Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2;
634  e->setInformation(Info);
635 
637  e->setRobustKernel(rk);
638  rk->setDelta(thHuberStereo);
639 
640  e->fx = pKFi->fx;
641  e->fy = pKFi->fy;
642  e->cx = pKFi->cx;
643  e->cy = pKFi->cy;
644  e->bf = pKFi->mbf;
645 
646  optimizer.addEdge(e);
647  vpEdgesStereo.push_back(e);
648  vpEdgeKFStereo.push_back(pKFi);
649  vpMapPointEdgeStereo.push_back(pMP);
650  }
651  }
652  }
653  }
654 
655  if(pbStopFlag)
656  if(*pbStopFlag)
657  return;
658 
659  optimizer.initializeOptimization();
660  optimizer.optimize(5);
661 
662  bool bDoMore= true;
663 
664  if(pbStopFlag)
665  if(*pbStopFlag)
666  bDoMore = false;
667 
668  if(bDoMore)
669  {
670 
671  // Check inlier observations
672  for(size_t i=0, iend=vpEdgesMono.size(); i<iend;i++)
673  {
674  g2o::EdgeSE3ProjectXYZ* e = vpEdgesMono[i];
675  MapPoint* pMP = vpMapPointEdgeMono[i];
676 
677  if(pMP->isBad())
678  continue;
679 
680  if(e->chi2()>5.991 || !e->isDepthPositive())
681  {
682  e->setLevel(1);
683  }
684 
685  e->setRobustKernel(0);
686  }
687 
688  for(size_t i=0, iend=vpEdgesStereo.size(); i<iend;i++)
689  {
690  g2o::EdgeStereoSE3ProjectXYZ* e = vpEdgesStereo[i];
691  MapPoint* pMP = vpMapPointEdgeStereo[i];
692 
693  if(pMP->isBad())
694  continue;
695 
696  if(e->chi2()>7.815 || !e->isDepthPositive())
697  {
698  e->setLevel(1);
699  }
700 
701  e->setRobustKernel(0);
702  }
703 
704  // Optimize again without the outliers
705 
706  optimizer.initializeOptimization(0);
707  optimizer.optimize(10);
708 
709  }
710 
711  vector<pair<KeyFrame*,MapPoint*> > vToErase;
712  vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size());
713 
714  // Check inlier observations
715  for(size_t i=0, iend=vpEdgesMono.size(); i<iend;i++)
716  {
717  g2o::EdgeSE3ProjectXYZ* e = vpEdgesMono[i];
718  MapPoint* pMP = vpMapPointEdgeMono[i];
719 
720  if(pMP->isBad())
721  continue;
722 
723  if(e->chi2()>5.991 || !e->isDepthPositive())
724  {
725  KeyFrame* pKFi = vpEdgeKFMono[i];
726  vToErase.push_back(make_pair(pKFi,pMP));
727  }
728  }
729 
730  for(size_t i=0, iend=vpEdgesStereo.size(); i<iend;i++)
731  {
732  g2o::EdgeStereoSE3ProjectXYZ* e = vpEdgesStereo[i];
733  MapPoint* pMP = vpMapPointEdgeStereo[i];
734 
735  if(pMP->isBad())
736  continue;
737 
738  if(e->chi2()>7.815 || !e->isDepthPositive())
739  {
740  KeyFrame* pKFi = vpEdgeKFStereo[i];
741  vToErase.push_back(make_pair(pKFi,pMP));
742  }
743  }
744 
745  // Get Map Mutex
746  unique_lock<mutex> lock(pMap->mMutexMapUpdate);
747 
748  if(!vToErase.empty())
749  {
750  for(size_t i=0;i<vToErase.size();i++)
751  {
752  KeyFrame* pKFi = vToErase[i].first;
753  MapPoint* pMPi = vToErase[i].second;
754  pKFi->EraseMapPointMatch(pMPi);
755  pMPi->EraseObservation(pKFi);
756  }
757  }
758 
759  // Recover optimized data
760 
761  //Keyframes
762  for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++)
763  {
764  KeyFrame* pKF = *lit;
765  g2o::VertexSE3Expmap* vSE3 = static_cast<g2o::VertexSE3Expmap*>(optimizer.vertex(pKF->mnId));
766  g2o::SE3Quat SE3quat = vSE3->estimate();
767  pKF->SetPose(Converter::toCvMat(SE3quat));
768  }
769 
770  //Points
771  for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
772  {
773  MapPoint* pMP = *lit;
774  g2o::VertexSBAPointXYZ* vPoint = static_cast<g2o::VertexSBAPointXYZ*>(optimizer.vertex(pMP->mnId+maxKFid+1));
775  pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate()));
776  pMP->UpdateNormalAndDepth();
777  }
778 }
779 
780 
782  const LoopClosing::KeyFrameAndPose &NonCorrectedSim3,
783  const LoopClosing::KeyFrameAndPose &CorrectedSim3,
784  const map<KeyFrame *, set<KeyFrame *> > &LoopConnections, const bool &bFixScale)
785 {
786  // Setup optimizer
787  g2o::SparseOptimizer optimizer;
788  optimizer.setVerbose(false);
791  g2o::BlockSolver_7_3 * solver_ptr= new g2o::BlockSolver_7_3(linearSolver);
793 
794  solver->setUserLambdaInit(1e-16);
795  optimizer.setAlgorithm(solver);
796 
797  const vector<KeyFrame*> vpKFs = pMap->GetAllKeyFrames();
798  const vector<MapPoint*> vpMPs = pMap->GetAllMapPoints();
799 
800  const unsigned int nMaxKFid = pMap->GetMaxKFid();
801 
802  vector<g2o::Sim3,Eigen::aligned_allocator<g2o::Sim3> > vScw(nMaxKFid+1);
803  vector<g2o::Sim3,Eigen::aligned_allocator<g2o::Sim3> > vCorrectedSwc(nMaxKFid+1);
804  vector<g2o::VertexSim3Expmap*> vpVertices(nMaxKFid+1);
805 
806  const int minFeat = 100;
807 
808  // Set KeyFrame vertices
809  for(size_t i=0, iend=vpKFs.size(); i<iend;i++)
810  {
811  KeyFrame* pKF = vpKFs[i];
812  if(pKF->isBad())
813  continue;
815 
816  const int nIDi = pKF->mnId;
817 
818  LoopClosing::KeyFrameAndPose::const_iterator it = CorrectedSim3.find(pKF);
819 
820  if(it!=CorrectedSim3.end())
821  {
822  vScw[nIDi] = it->second;
823  VSim3->setEstimate(it->second);
824  }
825  else
826  {
827  Eigen::Matrix<double,3,3> Rcw = Converter::toMatrix3d(pKF->GetRotation());
828  Eigen::Matrix<double,3,1> tcw = Converter::toVector3d(pKF->GetTranslation());
829  g2o::Sim3 Siw(Rcw,tcw,1.0);
830  vScw[nIDi] = Siw;
831  VSim3->setEstimate(Siw);
832  }
833 
834  if(pKF==pLoopKF)
835  VSim3->setFixed(true);
836 
837  VSim3->setId(nIDi);
838  VSim3->setMarginalized(false);
839  VSim3->_fix_scale = bFixScale;
840 
841  optimizer.addVertex(VSim3);
842 
843  vpVertices[nIDi]=VSim3;
844  }
845 
846 
847  set<pair<long unsigned int,long unsigned int> > sInsertedEdges;
848 
849  const Eigen::Matrix<double,7,7> matLambda = Eigen::Matrix<double,7,7>::Identity();
850 
851  // Set Loop edges
852  for(map<KeyFrame *, set<KeyFrame *> >::const_iterator mit = LoopConnections.begin(), mend=LoopConnections.end(); mit!=mend; mit++)
853  {
854  KeyFrame* pKF = mit->first;
855  const long unsigned int nIDi = pKF->mnId;
856  const set<KeyFrame*> &spConnections = mit->second;
857  const g2o::Sim3 Siw = vScw[nIDi];
858  const g2o::Sim3 Swi = Siw.inverse();
859 
860  for(set<KeyFrame*>::const_iterator sit=spConnections.begin(), send=spConnections.end(); sit!=send; sit++)
861  {
862  const long unsigned int nIDj = (*sit)->mnId;
863  if((nIDi!=pCurKF->mnId || nIDj!=pLoopKF->mnId) && pKF->GetWeight(*sit)<minFeat)
864  continue;
865 
866  const g2o::Sim3 Sjw = vScw[nIDj];
867  const g2o::Sim3 Sji = Sjw * Swi;
868 
869  g2o::EdgeSim3* e = new g2o::EdgeSim3();
870  e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(nIDj)));
871  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(nIDi)));
872  e->setMeasurement(Sji);
873 
874  e->information() = matLambda;
875 
876  optimizer.addEdge(e);
877 
878  sInsertedEdges.insert(make_pair(min(nIDi,nIDj),max(nIDi,nIDj)));
879  }
880  }
881 
882  // Set normal edges
883  for(size_t i=0, iend=vpKFs.size(); i<iend; i++)
884  {
885  KeyFrame* pKF = vpKFs[i];
886 
887  const int nIDi = pKF->mnId;
888 
889  g2o::Sim3 Swi;
890 
891  LoopClosing::KeyFrameAndPose::const_iterator iti = NonCorrectedSim3.find(pKF);
892 
893  if(iti!=NonCorrectedSim3.end())
894  Swi = (iti->second).inverse();
895  else
896  Swi = vScw[nIDi].inverse();
897 
898  KeyFrame* pParentKF = pKF->GetParent();
899 
900  // Spanning tree edge
901  if(pParentKF)
902  {
903  int nIDj = pParentKF->mnId;
904 
905  g2o::Sim3 Sjw;
906 
907  LoopClosing::KeyFrameAndPose::const_iterator itj = NonCorrectedSim3.find(pParentKF);
908 
909  if(itj!=NonCorrectedSim3.end())
910  Sjw = itj->second;
911  else
912  Sjw = vScw[nIDj];
913 
914  g2o::Sim3 Sji = Sjw * Swi;
915 
916  g2o::EdgeSim3* e = new g2o::EdgeSim3();
917  e->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(nIDj)));
918  e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(nIDi)));
919  e->setMeasurement(Sji);
920 
921  e->information() = matLambda;
922  optimizer.addEdge(e);
923  }
924 
925  // Loop edges
926  const set<KeyFrame*> sLoopEdges = pKF->GetLoopEdges();
927  for(set<KeyFrame*>::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++)
928  {
929  KeyFrame* pLKF = *sit;
930  if(pLKF->mnId<pKF->mnId)
931  {
932  g2o::Sim3 Slw;
933 
934  LoopClosing::KeyFrameAndPose::const_iterator itl = NonCorrectedSim3.find(pLKF);
935 
936  if(itl!=NonCorrectedSim3.end())
937  Slw = itl->second;
938  else
939  Slw = vScw[pLKF->mnId];
940 
941  g2o::Sim3 Sli = Slw * Swi;
942  g2o::EdgeSim3* el = new g2o::EdgeSim3();
943  el->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pLKF->mnId)));
944  el->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(nIDi)));
945  el->setMeasurement(Sli);
946  el->information() = matLambda;
947  optimizer.addEdge(el);
948  }
949  }
950 
951  // Covisibility graph edges
952  const vector<KeyFrame*> vpConnectedKFs = pKF->GetCovisiblesByWeight(minFeat);
953  for(vector<KeyFrame*>::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++)
954  {
955  KeyFrame* pKFn = *vit;
956  if(pKFn && pKFn!=pParentKF && !pKF->hasChild(pKFn) && !sLoopEdges.count(pKFn))
957  {
958  if(!pKFn->isBad() && pKFn->mnId<pKF->mnId)
959  {
960  if(sInsertedEdges.count(make_pair(min(pKF->mnId,pKFn->mnId),max(pKF->mnId,pKFn->mnId))))
961  continue;
962 
963  g2o::Sim3 Snw;
964 
965  LoopClosing::KeyFrameAndPose::const_iterator itn = NonCorrectedSim3.find(pKFn);
966 
967  if(itn!=NonCorrectedSim3.end())
968  Snw = itn->second;
969  else
970  Snw = vScw[pKFn->mnId];
971 
972  g2o::Sim3 Sni = Snw * Swi;
973 
974  g2o::EdgeSim3* en = new g2o::EdgeSim3();
975  en->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(pKFn->mnId)));
976  en->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(nIDi)));
977  en->setMeasurement(Sni);
978  en->information() = matLambda;
979  optimizer.addEdge(en);
980  }
981  }
982  }
983  }
984 
985  // Optimize!
986  optimizer.initializeOptimization();
987  optimizer.optimize(20);
988 
989  unique_lock<mutex> lock(pMap->mMutexMapUpdate);
990 
991  // SE3 Pose Recovering. Sim3:[sR t;0 1] -> SE3:[R t/s;0 1]
992  for(size_t i=0;i<vpKFs.size();i++)
993  {
994  KeyFrame* pKFi = vpKFs[i];
995 
996  const int nIDi = pKFi->mnId;
997 
998  g2o::VertexSim3Expmap* VSim3 = static_cast<g2o::VertexSim3Expmap*>(optimizer.vertex(nIDi));
999  g2o::Sim3 CorrectedSiw = VSim3->estimate();
1000  vCorrectedSwc[nIDi]=CorrectedSiw.inverse();
1001  Eigen::Matrix3d eigR = CorrectedSiw.rotation().toRotationMatrix();
1002  Eigen::Vector3d eigt = CorrectedSiw.translation();
1003  double s = CorrectedSiw.scale();
1004 
1005  eigt *=(1./s); //[R t/s;0 1]
1006 
1007  cv::Mat Tiw = Converter::toCvSE3(eigR,eigt);
1008 
1009  pKFi->SetPose(Tiw);
1010  }
1011 
1012  // Correct points. Transform to "non-optimized" reference keyframe pose and transform back with optimized pose
1013  for(size_t i=0, iend=vpMPs.size(); i<iend; i++)
1014  {
1015  MapPoint* pMP = vpMPs[i];
1016 
1017  if(pMP->isBad())
1018  continue;
1019 
1020  int nIDr;
1021  if(pMP->mnCorrectedByKF==pCurKF->mnId)
1022  {
1023  nIDr = pMP->mnCorrectedReference;
1024  }
1025  else
1026  {
1027  KeyFrame* pRefKF = pMP->GetReferenceKeyFrame();
1028  nIDr = pRefKF->mnId;
1029  }
1030 
1031 
1032  g2o::Sim3 Srw = vScw[nIDr];
1033  g2o::Sim3 correctedSwr = vCorrectedSwc[nIDr];
1034 
1035  cv::Mat P3Dw = pMP->GetWorldPos();
1036  Eigen::Matrix<double,3,1> eigP3Dw = Converter::toVector3d(P3Dw);
1037  Eigen::Matrix<double,3,1> eigCorrectedP3Dw = correctedSwr.map(Srw.map(eigP3Dw));
1038 
1039  cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw);
1040  pMP->SetWorldPos(cvCorrectedP3Dw);
1041 
1042  pMP->UpdateNormalAndDepth();
1043  }
1044 }
1045 
1046 int Optimizer::OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, vector<MapPoint *> &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale)
1047 {
1048  g2o::SparseOptimizer optimizer;
1049  g2o::BlockSolverX::LinearSolverType * linearSolver;
1050 
1052 
1053  g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver);
1054 
1056  optimizer.setAlgorithm(solver);
1057 
1058  // Calibration
1059  const cv::Mat &K1 = pKF1->mK;
1060  const cv::Mat &K2 = pKF2->mK;
1061 
1062  // Camera poses
1063  const cv::Mat R1w = pKF1->GetRotation();
1064  const cv::Mat t1w = pKF1->GetTranslation();
1065  const cv::Mat R2w = pKF2->GetRotation();
1066  const cv::Mat t2w = pKF2->GetTranslation();
1067 
1068  // Set Sim3 vertex
1070  vSim3->_fix_scale=bFixScale;
1071  vSim3->setEstimate(g2oS12);
1072  vSim3->setId(0);
1073  vSim3->setFixed(false);
1074  vSim3->_principle_point1[0] = K1.at<float>(0,2);
1075  vSim3->_principle_point1[1] = K1.at<float>(1,2);
1076  vSim3->_focal_length1[0] = K1.at<float>(0,0);
1077  vSim3->_focal_length1[1] = K1.at<float>(1,1);
1078  vSim3->_principle_point2[0] = K2.at<float>(0,2);
1079  vSim3->_principle_point2[1] = K2.at<float>(1,2);
1080  vSim3->_focal_length2[0] = K2.at<float>(0,0);
1081  vSim3->_focal_length2[1] = K2.at<float>(1,1);
1082  optimizer.addVertex(vSim3);
1083 
1084  // Set MapPoint vertices
1085  const int N = vpMatches1.size();
1086  const vector<MapPoint*> vpMapPoints1 = pKF1->GetMapPointMatches();
1087  vector<g2o::EdgeSim3ProjectXYZ*> vpEdges12;
1088  vector<g2o::EdgeInverseSim3ProjectXYZ*> vpEdges21;
1089  vector<size_t> vnIndexEdge;
1090 
1091  vnIndexEdge.reserve(2*N);
1092  vpEdges12.reserve(2*N);
1093  vpEdges21.reserve(2*N);
1094 
1095  const float deltaHuber = sqrt(th2);
1096 
1097  int nCorrespondences = 0;
1098 
1099  for(int i=0; i<N; i++)
1100  {
1101  if(!vpMatches1[i])
1102  continue;
1103 
1104  MapPoint* pMP1 = vpMapPoints1[i];
1105  MapPoint* pMP2 = vpMatches1[i];
1106 
1107  const int id1 = 2*i+1;
1108  const int id2 = 2*(i+1);
1109 
1110  const int i2 = pMP2->GetIndexInKeyFrame(pKF2);
1111 
1112  if(pMP1 && pMP2)
1113  {
1114  if(!pMP1->isBad() && !pMP2->isBad() && i2>=0)
1115  {
1117  cv::Mat P3D1w = pMP1->GetWorldPos();
1118  cv::Mat P3D1c = R1w*P3D1w + t1w;
1119  vPoint1->setEstimate(Converter::toVector3d(P3D1c));
1120  vPoint1->setId(id1);
1121  vPoint1->setFixed(true);
1122  optimizer.addVertex(vPoint1);
1123 
1125  cv::Mat P3D2w = pMP2->GetWorldPos();
1126  cv::Mat P3D2c = R2w*P3D2w + t2w;
1127  vPoint2->setEstimate(Converter::toVector3d(P3D2c));
1128  vPoint2->setId(id2);
1129  vPoint2->setFixed(true);
1130  optimizer.addVertex(vPoint2);
1131  }
1132  else
1133  continue;
1134  }
1135  else
1136  continue;
1137 
1138  nCorrespondences++;
1139 
1140  // Set edge x1 = S12*X2
1141  Eigen::Matrix<double,2,1> obs1;
1142  const cv::KeyPoint &kpUn1 = pKF1->mvKeysUn[i];
1143  obs1 << kpUn1.pt.x, kpUn1.pt.y;
1144 
1146  e12->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id2)));
1147  e12->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(0)));
1148  e12->setMeasurement(obs1);
1149  const float &invSigmaSquare1 = pKF1->mvInvLevelSigma2[kpUn1.octave];
1150  e12->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare1);
1151 
1153  e12->setRobustKernel(rk1);
1154  rk1->setDelta(deltaHuber);
1155  optimizer.addEdge(e12);
1156 
1157  // Set edge x2 = S21*X1
1158  Eigen::Matrix<double,2,1> obs2;
1159  const cv::KeyPoint &kpUn2 = pKF2->mvKeysUn[i2];
1160  obs2 << kpUn2.pt.x, kpUn2.pt.y;
1161 
1163 
1164  e21->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(id1)));
1165  e21->setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.vertex(0)));
1166  e21->setMeasurement(obs2);
1167  float invSigmaSquare2 = pKF2->mvInvLevelSigma2[kpUn2.octave];
1168  e21->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare2);
1169 
1171  e21->setRobustKernel(rk2);
1172  rk2->setDelta(deltaHuber);
1173  optimizer.addEdge(e21);
1174 
1175  vpEdges12.push_back(e12);
1176  vpEdges21.push_back(e21);
1177  vnIndexEdge.push_back(i);
1178  }
1179 
1180  // Optimize!
1181  optimizer.initializeOptimization();
1182  optimizer.optimize(5);
1183 
1184  // Check inliers
1185  int nBad=0;
1186  for(size_t i=0; i<vpEdges12.size();i++)
1187  {
1188  g2o::EdgeSim3ProjectXYZ* e12 = vpEdges12[i];
1189  g2o::EdgeInverseSim3ProjectXYZ* e21 = vpEdges21[i];
1190  if(!e12 || !e21)
1191  continue;
1192 
1193  if(e12->chi2()>th2 || e21->chi2()>th2)
1194  {
1195  size_t idx = vnIndexEdge[i];
1196  vpMatches1[idx]=static_cast<MapPoint*>(NULL);
1197  optimizer.removeEdge(e12);
1198  optimizer.removeEdge(e21);
1199  vpEdges12[i]=static_cast<g2o::EdgeSim3ProjectXYZ*>(NULL);
1200  vpEdges21[i]=static_cast<g2o::EdgeInverseSim3ProjectXYZ*>(NULL);
1201  nBad++;
1202  }
1203  }
1204 
1205  int nMoreIterations;
1206  if(nBad>0)
1207  nMoreIterations=10;
1208  else
1209  nMoreIterations=5;
1210 
1211  if(nCorrespondences-nBad<10)
1212  return 0;
1213 
1214  // Optimize again only with inliers
1215 
1216  optimizer.initializeOptimization();
1217  optimizer.optimize(nMoreIterations);
1218 
1219  int nIn = 0;
1220  for(size_t i=0; i<vpEdges12.size();i++)
1221  {
1222  g2o::EdgeSim3ProjectXYZ* e12 = vpEdges12[i];
1223  g2o::EdgeInverseSim3ProjectXYZ* e21 = vpEdges21[i];
1224  if(!e12 || !e21)
1225  continue;
1226 
1227  if(e12->chi2()>th2 || e21->chi2()>th2)
1228  {
1229  size_t idx = vnIndexEdge[i];
1230  vpMatches1[idx]=static_cast<MapPoint*>(NULL);
1231  }
1232  else
1233  nIn++;
1234  }
1235 
1236  // Recover optimized Sim3
1237  g2o::VertexSim3Expmap* vSim3_recov = static_cast<g2o::VertexSim3Expmap*>(optimizer.vertex(0));
1238  g2oS12= vSim3_recov->estimate();
1239 
1240  return nIn;
1241 }
1242 
1243 
1244 } //namespace ORB_SLAM
Definition: sim3.h:41
cv::Mat GetRotation()
Definition: KeyFrame.cc:111
void EraseMapPointMatch(const size_t &idx)
Definition: KeyFrame.cc:216
static Eigen::Matrix< double, 3, 3 > toMatrix3d(const cv::Mat &cvMat3)
Definition: Converter.cc:126
long unsigned int mnBALocalForKF
Definition: MapPoint.h:103
static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale)
Definition: Optimizer.cc:1046
std::vector< MapPoint * > mvpMapPoints
Definition: Frame.h:153
map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< KeyFrame *const, g2o::Sim3 > > > KeyFrameAndPose
Definition: LoopClosing.h:50
long unsigned int GetMaxKFid()
Definition: Map.cc:112
BlockSolver< BlockSolverTraits< 6, 3 > > BlockSolver_6_3
Definition: block_solver.h:182
const std::vector< cv::KeyPoint > mvKeysUn
Definition: KeyFrame.h:165
long unsigned int mnBAGlobalForKF
Definition: MapPoint.h:111
static float fy
Definition: Frame.h:114
const float mbf
Definition: KeyFrame.h:158
Huber Cost Function.
cv::Mat GetPose()
Definition: KeyFrame.cc:86
std::vector< KeyFrame * > GetAllKeyFrames()
Definition: Map.cc:82
long unsigned int mnCorrectedByKF
Definition: MapPoint.h:108
static float cx
Definition: Frame.h:115
static cv::Mat toCvSE3(const Eigen::Matrix< double, 3, 3 > &R, const Eigen::Matrix< double, 3, 1 > &t)
Definition: Converter.cc:92
virtual double chi2() const
computes the chi2 based on the cached error value, only valid after computeError has been called...
Definition: base_edge.h:58
static float fx
Definition: Frame.h:113
std::mutex mMutexMapUpdate
Definition: Map.h:65
Implementation of the Levenberg Algorithm.
XmlRpcServer s
static float cy
Definition: Frame.h:116
int optimize(int iterations, bool online=false)
std::vector< KeyFrame * > GetCovisiblesByWeight(const int &w)
Definition: KeyFrame.cc:184
std::set< KeyFrame * > GetLoopEdges()
Definition: KeyFrame.cc:425
cv::Mat GetWorldPos()
Definition: MapPoint.cc:80
long unsigned int mnBAGlobalForKF
Definition: KeyFrame.h:155
std::vector< MapPoint * > GetMapPointMatches()
Definition: KeyFrame.cc:277
std::vector< bool > mvbOutlier
Definition: Frame.h:156
Sim3 inverse() const
Definition: sim3.h:233
const InformationType & information() const
information matrix of the constraint
Definition: base_edge.h:69
virtual void setMeasurement(const Measurement &m)
Definition: base_edge.h:78
void setRobustKernel(RobustKernel *ptr)
linear solver using dense cholesky decomposition
static cv::Mat toCvMat(const g2o::SE3Quat &SE3)
Definition: Converter.cc:49
const Vector3d & translation() const
Definition: sim3.h:280
void setVertex(size_t i, Vertex *v)
Definition: hyper_graph.h:148
void UpdateNormalAndDepth()
Definition: MapPoint.cc:330
virtual void setDelta(double delta)
std::vector< cv::KeyPoint > mvKeysUn
Definition: Frame.h:138
Point vertex, XYZ.
Definition: types_sba.h:40
std::vector< MapPoint * > GetAllMapPoints()
Definition: Map.cc:88
Vertex * vertex(int id)
returns the vertex number id appropriately casted
const cv::Mat mK
Definition: KeyFrame.h:190
SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential ...
Traits::LinearSolverType LinearSolverType
Definition: block_solver.h:111
const float cx
Definition: KeyFrame.h:158
virtual void setId(int id)
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id ...
static std::mutex mGlobalMutex
Definition: MapPoint.h:114
static void GlobalBundleAdjustemnt(Map *pMap, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
Definition: Optimizer.cc:41
const std::vector< float > mvInvLevelSigma2
Definition: KeyFrame.h:183
virtual bool removeVertex(HyperGraph::Vertex *v)
std::map< KeyFrame *, size_t > GetObservations()
Definition: MapPoint.cc:139
static void OptimizeEssentialGraph(Map *pMap, KeyFrame *pLoopKF, KeyFrame *pCurKF, const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, const LoopClosing::KeyFrameAndPose &CorrectedSim3, const map< KeyFrame *, set< KeyFrame * > > &LoopConnections, const bool &bFixScale)
Definition: Optimizer.cc:781
std::vector< float > mvuRight
Definition: Frame.h:142
const float fx
Definition: KeyFrame.h:158
long unsigned int mnBAFixedForKF
Definition: KeyFrame.h:142
void setVerbose(bool verbose)
cv::Mat GetTranslation()
Definition: KeyFrame.cc:117
const EdgeSet & edges() const
Definition: hyper_graph.h:182
cv::Mat mTcw
Definition: Frame.h:164
KeyFrame * GetReferenceKeyFrame()
Definition: MapPoint.cc:92
void setForceStopFlag(bool *flag)
void setAlgorithm(OptimizationAlgorithm *algorithm)
static Eigen::Matrix< double, 3, 1 > toVector3d(const cv::Mat &cvVector)
Definition: Converter.cc:110
linear solver which uses the sparse Cholesky solver from Eigen
void SetWorldPos(const cv::Mat &Pos)
Definition: MapPoint.cc:73
int GetWeight(KeyFrame *pKF)
Definition: KeyFrame.cc:201
Info
static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT)
Definition: Converter.cc:37
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
static void BundleAdjustment(const std::vector< KeyFrame * > &vpKF, const std::vector< MapPoint * > &vpMP, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
Definition: Optimizer.cc:49
static int PoseOptimization(Frame *pFrame)
Definition: Optimizer.cc:239
const float cy
Definition: KeyFrame.h:158
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:104
void SetPose(const cv::Mat &Tcw)
Definition: KeyFrame.cc:70
std::vector< KeyFrame * > GetVectorCovisibleKeyFrames()
Definition: KeyFrame.cc:168
long unsigned int mnBALocalForKF
Definition: KeyFrame.h:141
void setUserLambdaInit(double lambda)
specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to com...
static void LocalBundleAdjustment(KeyFrame *pKF, bool *pbStopFlag, Map *pMap)
Definition: Optimizer.cc:453
bool hasChild(KeyFrame *pKF)
Definition: KeyFrame.cc:412
7D edge between two Vertex7
vector< float > mvInvLevelSigma2
Definition: Frame.h:180
const double & scale() const
Definition: sim3.h:288
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
BlockSolver< BlockSolverTraits< 7, 3 > > BlockSolver_7_3
Definition: block_solver.h:184
int min(int a, int b)
const float fy
Definition: KeyFrame.h:158
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:102
const std::vector< float > mvuRight
Definition: KeyFrame.h:166
Implementation of a solver operating on the blocks of the Hessian.
Definition: block_solver.h:97
int GetIndexInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:315
void SetPose(cv::Mat Tcw)
Definition: Frame.cc:255
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
void setLevel(int l)
sets the level of the edge
Vector3d map(const Vector3d &xyz) const
Definition: sim3.h:144
long unsigned int mnCorrectedReference
Definition: MapPoint.h:109
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
virtual bool removeEdge(Edge *e)
removes a vertex from the graph. Returns true on success (edge was present)
void setInformation(const InformationType &information)
Definition: base_edge.h:71
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
long unsigned int mnId
Definition: KeyFrame.h:125
long unsigned int mnId
Definition: MapPoint.h:86
KeyFrame * GetParent()
Definition: KeyFrame.cc:406
const Quaterniond & rotation() const
Definition: sim3.h:284
BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > BlockSolverX
Definition: block_solver.h:180
void EraseObservation(KeyFrame *pKF)
Definition: MapPoint.cc:111


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