LocalMapping.cc
Go to the documentation of this file.
1 
21 #include "LocalMapping.h"
22 #include "LoopClosing.h"
23 #include "ORBmatcher.h"
24 #include "Optimizer.h"
25 
26 #include<mutex>
27 
28 namespace ORB_SLAM2
29 {
30 
31 LocalMapping::LocalMapping(Map *pMap, const float bMonocular):
32  mbMonocular(bMonocular), mbResetRequested(false), mbFinishRequested(false), mbFinished(true), mpMap(pMap),
33  mbAbortBA(false), mbStopped(false), mbStopRequested(false), mbNotStop(false), mbAcceptKeyFrames(true)
34 {
35 }
36 
38 {
39  mpLoopCloser = pLoopCloser;
40 }
41 
43 {
44  mpTracker=pTracker;
45 }
46 
48 {
49 
50  mbFinished = false;
51 
52  while(1)
53  {
54  // Tracking will see that Local Mapping is busy
55  SetAcceptKeyFrames(false);
56 
57  // Check if there are keyframes in the queue
58  if(CheckNewKeyFrames())
59  {
60  // BoW conversion and insertion in Map
62 
63  // Check recent MapPoints
65 
66  // Triangulate new MapPoints
68 
69  if(!CheckNewKeyFrames())
70  {
71  // Find more matches in neighbor keyframes and fuse point duplications
73  }
74 
75  mbAbortBA = false;
76 
77  if(!CheckNewKeyFrames() && !stopRequested())
78  {
79  // Local BA
80  if(mpMap->KeyFramesInMap()>2)
82 
83  // Check redundant local Keyframes
85  }
86 
88  }
89  else if(Stop())
90  {
91  // Safe area to stop
92  while(isStopped() && !CheckFinish())
93  {
94  std::this_thread::sleep_for(std::chrono::microseconds(3000));
95  }
96  if(CheckFinish())
97  break;
98  }
99 
101 
102  // Tracking will see that Local Mapping is busy
103  SetAcceptKeyFrames(true);
104 
105  if(CheckFinish())
106  break;
107 
108  std::this_thread::sleep_for(std::chrono::microseconds(3000));
109  }
110 
111  SetFinish();
112 }
113 
115 {
116  unique_lock<mutex> lock(mMutexNewKFs);
117  mlNewKeyFrames.push_back(pKF);
118  mbAbortBA=true;
119 }
120 
121 
123 {
124  unique_lock<mutex> lock(mMutexNewKFs);
125  return(!mlNewKeyFrames.empty());
126 }
127 
129 {
130  {
131  unique_lock<mutex> lock(mMutexNewKFs);
133  mlNewKeyFrames.pop_front();
134  }
135 
136  // Compute Bags of Words structures
138 
139  // Associate MapPoints to the new keyframe and update normal and descriptor
140  const vector<MapPoint*> vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
141 
142  for(size_t i=0; i<vpMapPointMatches.size(); i++)
143  {
144  MapPoint* pMP = vpMapPointMatches[i];
145  if(pMP)
146  {
147  if(!pMP->isBad())
148  {
150  {
152  pMP->UpdateNormalAndDepth();
154  }
155  else // this can only happen for new stereo points inserted by the Tracking
156  {
157  mlpRecentAddedMapPoints.push_back(pMP);
158  }
159  }
160  }
161  }
162 
163  // Update links in the Covisibility Graph
165 
166  // Insert Keyframe in Map
168 }
169 
171 {
172  // Check Recent Added MapPoints
173  list<MapPoint*>::iterator lit = mlpRecentAddedMapPoints.begin();
174  const unsigned long int nCurrentKFid = mpCurrentKeyFrame->mnId;
175 
176  int nThObs;
177  if(mbMonocular)
178  nThObs = 2;
179  else
180  nThObs = 3;
181  const int cnThObs = nThObs;
182 
183  while(lit!=mlpRecentAddedMapPoints.end())
184  {
185  MapPoint* pMP = *lit;
186  if(pMP->isBad())
187  {
188  lit = mlpRecentAddedMapPoints.erase(lit);
189  }
190  else if(pMP->GetFoundRatio()<0.25f )
191  {
192  pMP->SetBadFlag();
193  lit = mlpRecentAddedMapPoints.erase(lit);
194  }
195  else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=2 && pMP->Observations()<=cnThObs)
196  {
197  pMP->SetBadFlag();
198  lit = mlpRecentAddedMapPoints.erase(lit);
199  }
200  else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=3)
201  lit = mlpRecentAddedMapPoints.erase(lit);
202  else
203  lit++;
204  }
205 }
206 
208 {
209  // Retrieve neighbor keyframes in covisibility graph
210  int nn = 10;
211  if(mbMonocular)
212  nn=20;
213  const vector<KeyFrame*> vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn);
214 
215  ORBmatcher matcher(0.6,false);
216 
217  cv::Mat Rcw1 = mpCurrentKeyFrame->GetRotation();
218  cv::Mat Rwc1 = Rcw1.t();
219  cv::Mat tcw1 = mpCurrentKeyFrame->GetTranslation();
220  cv::Mat Tcw1(3,4,CV_32F);
221  Rcw1.copyTo(Tcw1.colRange(0,3));
222  tcw1.copyTo(Tcw1.col(3));
223  cv::Mat Ow1 = mpCurrentKeyFrame->GetCameraCenter();
224 
225  const float &fx1 = mpCurrentKeyFrame->fx;
226  const float &fy1 = mpCurrentKeyFrame->fy;
227  const float &cx1 = mpCurrentKeyFrame->cx;
228  const float &cy1 = mpCurrentKeyFrame->cy;
229  const float &invfx1 = mpCurrentKeyFrame->invfx;
230  const float &invfy1 = mpCurrentKeyFrame->invfy;
231 
232  const float ratioFactor = 1.5f*mpCurrentKeyFrame->mfScaleFactor;
233 
234  int nnew=0;
235 
236  // Search matches with epipolar restriction and triangulate
237  for(size_t i=0; i<vpNeighKFs.size(); i++)
238  {
239  if(i>0 && CheckNewKeyFrames())
240  return;
241 
242  KeyFrame* pKF2 = vpNeighKFs[i];
243 
244  // Check first that baseline is not too short
245  cv::Mat Ow2 = pKF2->GetCameraCenter();
246  cv::Mat vBaseline = Ow2-Ow1;
247  const float baseline = cv::norm(vBaseline);
248 
249  if(!mbMonocular)
250  {
251  if(baseline<pKF2->mb)
252  continue;
253  }
254  else
255  {
256  const float medianDepthKF2 = pKF2->ComputeSceneMedianDepth(2);
257  const float ratioBaselineDepth = baseline/medianDepthKF2;
258 
259  if(ratioBaselineDepth<0.01)
260  continue;
261  }
262 
263  // Compute Fundamental Matrix
264  cv::Mat F12 = ComputeF12(mpCurrentKeyFrame,pKF2);
265 
266  // Search matches that fullfil epipolar constraint
267  vector<pair<size_t,size_t> > vMatchedIndices;
268  matcher.SearchForTriangulation(mpCurrentKeyFrame,pKF2,F12,vMatchedIndices,false);
269 
270  cv::Mat Rcw2 = pKF2->GetRotation();
271  cv::Mat Rwc2 = Rcw2.t();
272  cv::Mat tcw2 = pKF2->GetTranslation();
273  cv::Mat Tcw2(3,4,CV_32F);
274  Rcw2.copyTo(Tcw2.colRange(0,3));
275  tcw2.copyTo(Tcw2.col(3));
276 
277  const float &fx2 = pKF2->fx;
278  const float &fy2 = pKF2->fy;
279  const float &cx2 = pKF2->cx;
280  const float &cy2 = pKF2->cy;
281  const float &invfx2 = pKF2->invfx;
282  const float &invfy2 = pKF2->invfy;
283 
284  // Triangulate each match
285  const int nmatches = vMatchedIndices.size();
286  for(int ikp=0; ikp<nmatches; ikp++)
287  {
288  const int &idx1 = vMatchedIndices[ikp].first;
289  const int &idx2 = vMatchedIndices[ikp].second;
290 
291  const cv::KeyPoint &kp1 = mpCurrentKeyFrame->mvKeysUn[idx1];
292  const float kp1_ur=mpCurrentKeyFrame->mvuRight[idx1];
293  bool bStereo1 = kp1_ur>=0;
294 
295  const cv::KeyPoint &kp2 = pKF2->mvKeysUn[idx2];
296  const float kp2_ur = pKF2->mvuRight[idx2];
297  bool bStereo2 = kp2_ur>=0;
298 
299  // Check parallax between rays
300  cv::Mat xn1 = (cv::Mat_<float>(3,1) << (kp1.pt.x-cx1)*invfx1, (kp1.pt.y-cy1)*invfy1, 1.0);
301  cv::Mat xn2 = (cv::Mat_<float>(3,1) << (kp2.pt.x-cx2)*invfx2, (kp2.pt.y-cy2)*invfy2, 1.0);
302 
303  cv::Mat ray1 = Rwc1*xn1;
304  cv::Mat ray2 = Rwc2*xn2;
305  const float cosParallaxRays = ray1.dot(ray2)/(cv::norm(ray1)*cv::norm(ray2));
306 
307  float cosParallaxStereo = cosParallaxRays+1;
308  float cosParallaxStereo1 = cosParallaxStereo;
309  float cosParallaxStereo2 = cosParallaxStereo;
310 
311  if(bStereo1)
312  cosParallaxStereo1 = cos(2*atan2(mpCurrentKeyFrame->mb/2,mpCurrentKeyFrame->mvDepth[idx1]));
313  else if(bStereo2)
314  cosParallaxStereo2 = cos(2*atan2(pKF2->mb/2,pKF2->mvDepth[idx2]));
315 
316  cosParallaxStereo = min(cosParallaxStereo1,cosParallaxStereo2);
317 
318  cv::Mat x3D;
319  if(cosParallaxRays<cosParallaxStereo && cosParallaxRays>0 && (bStereo1 || bStereo2 || cosParallaxRays<0.9998))
320  {
321  // Linear Triangulation Method
322  cv::Mat A(4,4,CV_32F);
323  A.row(0) = xn1.at<float>(0)*Tcw1.row(2)-Tcw1.row(0);
324  A.row(1) = xn1.at<float>(1)*Tcw1.row(2)-Tcw1.row(1);
325  A.row(2) = xn2.at<float>(0)*Tcw2.row(2)-Tcw2.row(0);
326  A.row(3) = xn2.at<float>(1)*Tcw2.row(2)-Tcw2.row(1);
327 
328  cv::Mat w,u,vt;
329  cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV);
330 
331  x3D = vt.row(3).t();
332 
333  if(x3D.at<float>(3)==0)
334  continue;
335 
336  // Euclidean coordinates
337  x3D = x3D.rowRange(0,3)/x3D.at<float>(3);
338 
339  }
340  else if(bStereo1 && cosParallaxStereo1<cosParallaxStereo2)
341  {
342  x3D = mpCurrentKeyFrame->UnprojectStereo(idx1);
343  }
344  else if(bStereo2 && cosParallaxStereo2<cosParallaxStereo1)
345  {
346  x3D = pKF2->UnprojectStereo(idx2);
347  }
348  else
349  continue; //No stereo and very low parallax
350 
351  cv::Mat x3Dt = x3D.t();
352 
353  //Check triangulation in front of cameras
354  float z1 = Rcw1.row(2).dot(x3Dt)+tcw1.at<float>(2);
355  if(z1<=0)
356  continue;
357 
358  float z2 = Rcw2.row(2).dot(x3Dt)+tcw2.at<float>(2);
359  if(z2<=0)
360  continue;
361 
362  //Check reprojection error in first keyframe
363  const float &sigmaSquare1 = mpCurrentKeyFrame->mvLevelSigma2[kp1.octave];
364  const float x1 = Rcw1.row(0).dot(x3Dt)+tcw1.at<float>(0);
365  const float y1 = Rcw1.row(1).dot(x3Dt)+tcw1.at<float>(1);
366  const float invz1 = 1.0/z1;
367 
368  if(!bStereo1)
369  {
370  float u1 = fx1*x1*invz1+cx1;
371  float v1 = fy1*y1*invz1+cy1;
372  float errX1 = u1 - kp1.pt.x;
373  float errY1 = v1 - kp1.pt.y;
374  if((errX1*errX1+errY1*errY1)>5.991*sigmaSquare1)
375  continue;
376  }
377  else
378  {
379  float u1 = fx1*x1*invz1+cx1;
380  float u1_r = u1 - mpCurrentKeyFrame->mbf*invz1;
381  float v1 = fy1*y1*invz1+cy1;
382  float errX1 = u1 - kp1.pt.x;
383  float errY1 = v1 - kp1.pt.y;
384  float errX1_r = u1_r - kp1_ur;
385  if((errX1*errX1+errY1*errY1+errX1_r*errX1_r)>7.8*sigmaSquare1)
386  continue;
387  }
388 
389  //Check reprojection error in second keyframe
390  const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave];
391  const float x2 = Rcw2.row(0).dot(x3Dt)+tcw2.at<float>(0);
392  const float y2 = Rcw2.row(1).dot(x3Dt)+tcw2.at<float>(1);
393  const float invz2 = 1.0/z2;
394  if(!bStereo2)
395  {
396  float u2 = fx2*x2*invz2+cx2;
397  float v2 = fy2*y2*invz2+cy2;
398  float errX2 = u2 - kp2.pt.x;
399  float errY2 = v2 - kp2.pt.y;
400  if((errX2*errX2+errY2*errY2)>5.991*sigmaSquare2)
401  continue;
402  }
403  else
404  {
405  float u2 = fx2*x2*invz2+cx2;
406  float u2_r = u2 - mpCurrentKeyFrame->mbf*invz2;
407  float v2 = fy2*y2*invz2+cy2;
408  float errX2 = u2 - kp2.pt.x;
409  float errY2 = v2 - kp2.pt.y;
410  float errX2_r = u2_r - kp2_ur;
411  if((errX2*errX2+errY2*errY2+errX2_r*errX2_r)>7.8*sigmaSquare2)
412  continue;
413  }
414 
415  //Check scale consistency
416  cv::Mat normal1 = x3D-Ow1;
417  float dist1 = cv::norm(normal1);
418 
419  cv::Mat normal2 = x3D-Ow2;
420  float dist2 = cv::norm(normal2);
421 
422  if(dist1==0 || dist2==0)
423  continue;
424 
425  const float ratioDist = dist2/dist1;
426  const float ratioOctave = mpCurrentKeyFrame->mvScaleFactors[kp1.octave]/pKF2->mvScaleFactors[kp2.octave];
427 
428  /*if(fabs(ratioDist-ratioOctave)>ratioFactor)
429  continue;*/
430  if(ratioDist*ratioFactor<ratioOctave || ratioDist>ratioOctave*ratioFactor)
431  continue;
432 
433  // Triangulation is succesfull
434  MapPoint* pMP = new MapPoint(x3D,mpCurrentKeyFrame,mpMap);
435 
437  pMP->AddObservation(pKF2,idx2);
438 
439  mpCurrentKeyFrame->AddMapPoint(pMP,idx1);
440  pKF2->AddMapPoint(pMP,idx2);
441 
443 
444  pMP->UpdateNormalAndDepth();
445 
446  mpMap->AddMapPoint(pMP);
447  mlpRecentAddedMapPoints.push_back(pMP);
448 
449  nnew++;
450  }
451  }
452 }
453 
455 {
456  // Retrieve neighbor keyframes
457  int nn = 10;
458  if(mbMonocular)
459  nn=20;
460  const vector<KeyFrame*> vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn);
461  vector<KeyFrame*> vpTargetKFs;
462  for(vector<KeyFrame*>::const_iterator vit=vpNeighKFs.begin(), vend=vpNeighKFs.end(); vit!=vend; vit++)
463  {
464  KeyFrame* pKFi = *vit;
465  if(pKFi->isBad() || pKFi->mnFuseTargetForKF == mpCurrentKeyFrame->mnId)
466  continue;
467  vpTargetKFs.push_back(pKFi);
469 
470  // Extend to some second neighbors
471  const vector<KeyFrame*> vpSecondNeighKFs = pKFi->GetBestCovisibilityKeyFrames(5);
472  for(vector<KeyFrame*>::const_iterator vit2=vpSecondNeighKFs.begin(), vend2=vpSecondNeighKFs.end(); vit2!=vend2; vit2++)
473  {
474  KeyFrame* pKFi2 = *vit2;
475  if(pKFi2->isBad() || pKFi2->mnFuseTargetForKF==mpCurrentKeyFrame->mnId || pKFi2->mnId==mpCurrentKeyFrame->mnId)
476  continue;
477  vpTargetKFs.push_back(pKFi2);
478  }
479  }
480 
481 
482  // Search matches by projection from current KF in target KFs
483  ORBmatcher matcher;
484  vector<MapPoint*> vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
485  for(vector<KeyFrame*>::iterator vit=vpTargetKFs.begin(), vend=vpTargetKFs.end(); vit!=vend; vit++)
486  {
487  KeyFrame* pKFi = *vit;
488 
489  matcher.Fuse(pKFi,vpMapPointMatches);
490  }
491 
492  // Search matches by projection from target KFs in current KF
493  vector<MapPoint*> vpFuseCandidates;
494  vpFuseCandidates.reserve(vpTargetKFs.size()*vpMapPointMatches.size());
495 
496  for(vector<KeyFrame*>::iterator vitKF=vpTargetKFs.begin(), vendKF=vpTargetKFs.end(); vitKF!=vendKF; vitKF++)
497  {
498  KeyFrame* pKFi = *vitKF;
499 
500  vector<MapPoint*> vpMapPointsKFi = pKFi->GetMapPointMatches();
501 
502  for(vector<MapPoint*>::iterator vitMP=vpMapPointsKFi.begin(), vendMP=vpMapPointsKFi.end(); vitMP!=vendMP; vitMP++)
503  {
504  MapPoint* pMP = *vitMP;
505  if(!pMP)
506  continue;
507  if(pMP->isBad() || pMP->mnFuseCandidateForKF == mpCurrentKeyFrame->mnId)
508  continue;
510  vpFuseCandidates.push_back(pMP);
511  }
512  }
513 
514  matcher.Fuse(mpCurrentKeyFrame,vpFuseCandidates);
515 
516 
517  // Update points
518  vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches();
519  for(size_t i=0, iend=vpMapPointMatches.size(); i<iend; i++)
520  {
521  MapPoint* pMP=vpMapPointMatches[i];
522  if(pMP)
523  {
524  if(!pMP->isBad())
525  {
527  pMP->UpdateNormalAndDepth();
528  }
529  }
530  }
531 
532  // Update connections in covisibility graph
534 }
535 
537 {
538  cv::Mat R1w = pKF1->GetRotation();
539  cv::Mat t1w = pKF1->GetTranslation();
540  cv::Mat R2w = pKF2->GetRotation();
541  cv::Mat t2w = pKF2->GetTranslation();
542 
543  cv::Mat R12 = R1w*R2w.t();
544  cv::Mat t12 = -R1w*R2w.t()*t2w+t1w;
545 
546  cv::Mat t12x = SkewSymmetricMatrix(t12);
547 
548  const cv::Mat &K1 = pKF1->mK;
549  const cv::Mat &K2 = pKF2->mK;
550 
551 
552  return K1.t().inv()*t12x*R12*K2.inv();
553 }
554 
556 {
557  unique_lock<mutex> lock(mMutexStop);
558  mbStopRequested = true;
559  unique_lock<mutex> lock2(mMutexNewKFs);
560  mbAbortBA = true;
561 }
562 
564 {
565  unique_lock<mutex> lock(mMutexStop);
566  if(mbStopRequested && !mbNotStop)
567  {
568  mbStopped = true;
569  cout << "Local Mapping STOP" << endl;
570  return true;
571  }
572 
573  return false;
574 }
575 
577 {
578  unique_lock<mutex> lock(mMutexStop);
579  return mbStopped;
580 }
581 
583 {
584  unique_lock<mutex> lock(mMutexStop);
585  return mbStopRequested;
586 }
587 
589 {
590  unique_lock<mutex> lock(mMutexStop);
591  unique_lock<mutex> lock2(mMutexFinish);
592  if(mbFinished)
593  return;
594  mbStopped = false;
595  mbStopRequested = false;
596  for(list<KeyFrame*>::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++)
597  delete *lit;
598  mlNewKeyFrames.clear();
599 
600  cout << "Local Mapping RELEASE" << endl;
601 }
602 
604 {
605  unique_lock<mutex> lock(mMutexAccept);
606  return mbAcceptKeyFrames;
607 }
608 
610 {
611  unique_lock<mutex> lock(mMutexAccept);
612  mbAcceptKeyFrames=flag;
613 }
614 
616 {
617  unique_lock<mutex> lock(mMutexStop);
618 
619  if(flag && mbStopped)
620  return false;
621 
622  mbNotStop = flag;
623 
624  return true;
625 }
626 
628 {
629  mbAbortBA = true;
630 }
631 
633 {
634  // Check redundant keyframes (only local keyframes)
635  // A keyframe is considered redundant if the 90% of the MapPoints it sees, are seen
636  // in at least other 3 keyframes (in the same or finer scale)
637  // We only consider close stereo points
638  vector<KeyFrame*> vpLocalKeyFrames = mpCurrentKeyFrame->GetVectorCovisibleKeyFrames();
639 
640  for(vector<KeyFrame*>::iterator vit=vpLocalKeyFrames.begin(), vend=vpLocalKeyFrames.end(); vit!=vend; vit++)
641  {
642  KeyFrame* pKF = *vit;
643  if(pKF->mnId==0)
644  continue;
645  const vector<MapPoint*> vpMapPoints = pKF->GetMapPointMatches();
646 
647  int nObs = 3;
648  const int thObs=nObs;
649  int nRedundantObservations=0;
650  int nMPs=0;
651  for(size_t i=0, iend=vpMapPoints.size(); i<iend; i++)
652  {
653  MapPoint* pMP = vpMapPoints[i];
654  if(pMP)
655  {
656  if(!pMP->isBad())
657  {
658  if(!mbMonocular)
659  {
660  if(pKF->mvDepth[i]>pKF->mThDepth || pKF->mvDepth[i]<0)
661  continue;
662  }
663 
664  nMPs++;
665  if(pMP->Observations()>thObs)
666  {
667  const int &scaleLevel = pKF->mvKeysUn[i].octave;
668  const map<KeyFrame*, size_t> observations = pMP->GetObservations();
669  int nObs=0;
670  for(map<KeyFrame*, size_t>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
671  {
672  KeyFrame* pKFi = mit->first;
673  if(pKFi==pKF)
674  continue;
675  const int &scaleLeveli = pKFi->mvKeysUn[mit->second].octave;
676 
677  if(scaleLeveli<=scaleLevel+1)
678  {
679  nObs++;
680  if(nObs>=thObs)
681  break;
682  }
683  }
684  if(nObs>=thObs)
685  {
686  nRedundantObservations++;
687  }
688  }
689  }
690  }
691  }
692 
693  if(nRedundantObservations>0.9*nMPs)
694  pKF->SetBadFlag();
695  }
696 }
697 
698 cv::Mat LocalMapping::SkewSymmetricMatrix(const cv::Mat &v)
699 {
700  return (cv::Mat_<float>(3,3) << 0, -v.at<float>(2), v.at<float>(1),
701  v.at<float>(2), 0,-v.at<float>(0),
702  -v.at<float>(1), v.at<float>(0), 0);
703 }
704 
706 {
707  {
708  unique_lock<mutex> lock(mMutexReset);
709  mbResetRequested = true;
710  }
711 
712  while(1)
713  {
714  {
715  unique_lock<mutex> lock2(mMutexReset);
716  if(!mbResetRequested)
717  break;
718  }
719  std::this_thread::sleep_for(std::chrono::microseconds(3000));
720  }
721 }
722 
724 {
725  unique_lock<mutex> lock(mMutexReset);
726  if(mbResetRequested)
727  {
728  mlNewKeyFrames.clear();
729  mlpRecentAddedMapPoints.clear();
730  mbResetRequested=false;
731  }
732 }
733 
735 {
736  unique_lock<mutex> lock(mMutexFinish);
737  mbFinishRequested = true;
738 }
739 
741 {
742  unique_lock<mutex> lock(mMutexFinish);
743  return mbFinishRequested;
744 }
745 
747 {
748  unique_lock<mutex> lock(mMutexFinish);
749  mbFinished = true;
750  unique_lock<mutex> lock2(mMutexStop);
751  mbStopped = true;
752 }
753 
755 {
756  unique_lock<mutex> lock(mMutexFinish);
757  return mbFinished;
758 }
759 
760 } //namespace ORB_SLAM
std::vector< KeyFrame * > GetBestCovisibilityKeyFrames(const int &N)
Definition: KeyFrame.cc:174
cv::Mat GetRotation()
Definition: KeyFrame.cc:111
const std::vector< cv::KeyPoint > mvKeysUn
Definition: KeyFrame.h:165
KeyFrame * mpCurrentKeyFrame
Definition: LocalMapping.h:109
cv::Mat GetCameraCenter()
Definition: KeyFrame.cc:98
const float invfx
Definition: KeyFrame.h:158
const std::vector< float > mvScaleFactors
Definition: KeyFrame.h:181
const float mbf
Definition: KeyFrame.h:158
float GetFoundRatio()
Definition: MapPoint.cc:236
void SetTracker(Tracking *pTracker)
Definition: LocalMapping.cc:42
const float mfScaleFactor
Definition: KeyFrame.h:179
long int mnFirstKFid
Definition: MapPoint.h:88
void AddMapPoint(MapPoint *pMP, const size_t &idx)
Definition: KeyFrame.cc:210
void InsertKeyFrame(KeyFrame *pKF)
Definition: LoopClosing.cc:90
cv::Mat UnprojectStereo(int i)
Definition: KeyFrame.cc:615
const std::vector< float > mvLevelSigma2
Definition: KeyFrame.h:182
const float mThDepth
Definition: KeyFrame.h:158
int SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, std::vector< pair< size_t, size_t > > &vMatchedPairs, const bool bOnlyStereo)
Definition: ORBmatcher.cc:657
std::vector< MapPoint * > GetMapPointMatches()
Definition: KeyFrame.cc:277
bool SetNotStop(bool flag)
const float invfy
Definition: KeyFrame.h:158
void AddObservation(KeyFrame *pKF, size_t idx)
Definition: MapPoint.cc:98
cv::Mat ComputeF12(KeyFrame *&pKF1, KeyFrame *&pKF2)
void UpdateNormalAndDepth()
Definition: MapPoint.cc:330
LocalMapping(Map *pMap, const float bMonocular)
Definition: LocalMapping.cc:31
void AddMapPoint(MapPoint *pMP)
Definition: Map.cc:40
const cv::Mat mK
Definition: KeyFrame.h:190
const float cx
Definition: KeyFrame.h:158
cv::Mat SkewSymmetricMatrix(const cv::Mat &v)
std::map< KeyFrame *, size_t > GetObservations()
Definition: MapPoint.cc:139
void InsertKeyFrame(KeyFrame *pKF)
long unsigned KeyFramesInMap()
Definition: Map.cc:100
const float fx
Definition: KeyFrame.h:158
cv::Mat GetTranslation()
Definition: KeyFrame.cc:117
const std::vector< float > mvDepth
Definition: KeyFrame.h:167
long unsigned int mnFuseTargetForKF
Definition: KeyFrame.h:138
LoopClosing * mpLoopCloser
Definition: LocalMapping.h:104
const float cy
Definition: KeyFrame.h:158
void SetLoopCloser(LoopClosing *pLoopCloser)
Definition: LocalMapping.cc:37
float ComputeSceneMedianDepth(const int q)
Definition: KeyFrame.cc:633
std::vector< KeyFrame * > GetVectorCovisibleKeyFrames()
Definition: KeyFrame.cc:168
void SetAcceptKeyFrames(bool flag)
static void LocalBundleAdjustment(KeyFrame *pKF, bool *pbStopFlag, Map *pMap)
Definition: Optimizer.cc:453
TFSIMD_FORCE_INLINE const tfScalar & w() const
int min(int a, int b)
const float fy
Definition: KeyFrame.h:158
const std::vector< float > mvuRight
Definition: KeyFrame.h:166
void AddKeyFrame(KeyFrame *pKF)
Definition: Map.cc:32
const float mb
Definition: KeyFrame.h:158
void ComputeDistinctiveDescriptors()
Definition: MapPoint.cc:242
void UpdateConnections()
Definition: KeyFrame.cc:289
long unsigned int mnId
Definition: KeyFrame.h:125
std::list< MapPoint * > mlpRecentAddedMapPoints
Definition: LocalMapping.h:111
bool IsInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:324
long unsigned int mnFuseCandidateForKF
Definition: MapPoint.h:104
std::list< KeyFrame * > mlNewKeyFrames
Definition: LocalMapping.h:107
int Fuse(KeyFrame *pKF, const vector< MapPoint * > &vpMapPoints, const float th=3.0)
Definition: ORBmatcher.cc:825


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