KeyFrame.cc
Go to the documentation of this file.
1 
21 #include "KeyFrame.h"
22 #include "Converter.h"
23 #include "ORBmatcher.h"
24 #include<mutex>
25 
26 namespace ORB_SLAM2
27 {
28 
29 long unsigned int KeyFrame::nNextId=0;
30 
32  mnFrameId(F.mnId), mTimeStamp(F.mTimeStamp), mnGridCols(FRAME_GRID_COLS), mnGridRows(FRAME_GRID_ROWS),
33  mfGridElementWidthInv(F.mfGridElementWidthInv), mfGridElementHeightInv(F.mfGridElementHeightInv),
34  mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0),
35  mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnBAGlobalForKF(0),
36  fx(F.fx), fy(F.fy), cx(F.cx), cy(F.cy), invfx(F.invfx), invfy(F.invfy),
37  mbf(F.mbf), mb(F.mb), mThDepth(F.mThDepth), N(F.N), mvKeys(F.mvKeys), mvKeysUn(F.mvKeysUn),
38  mvuRight(F.mvuRight), mvDepth(F.mvDepth), mDescriptors(F.mDescriptors.clone()),
39  mBowVec(F.mBowVec), mFeatVec(F.mFeatVec), mnScaleLevels(F.mnScaleLevels), mfScaleFactor(F.mfScaleFactor),
40  mfLogScaleFactor(F.mfLogScaleFactor), mvScaleFactors(F.mvScaleFactors), mvLevelSigma2(F.mvLevelSigma2),
41  mvInvLevelSigma2(F.mvInvLevelSigma2), mnMinX(F.mnMinX), mnMinY(F.mnMinY), mnMaxX(F.mnMaxX),
42  mnMaxY(F.mnMaxY), mK(F.mK), mvpMapPoints(F.mvpMapPoints), mpKeyFrameDB(pKFDB),
43  mpORBvocabulary(F.mpORBvocabulary), mbFirstConnection(true), mpParent(NULL), mbNotErase(false),
44  mbToBeErased(false), mbBad(false), mHalfBaseline(F.mb/2), mpMap(pMap)
45 {
46  mnId=nNextId++;
47 
48  mGrid.resize(mnGridCols);
49  for(int i=0; i<mnGridCols;i++)
50  {
51  mGrid[i].resize(mnGridRows);
52  for(int j=0; j<mnGridRows; j++)
53  mGrid[i][j] = F.mGrid[i][j];
54  }
55 
56  SetPose(F.mTcw);
57 }
58 
60 {
61  if(mBowVec.empty() || mFeatVec.empty())
62  {
63  vector<cv::Mat> vCurrentDesc = Converter::toDescriptorVector(mDescriptors);
64  // Feature vector associate features with nodes in the 4th level (from leaves up)
65  // We assume the vocabulary tree has 6 levels, change the 4 otherwise
66  mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4);
67  }
68 }
69 
70 void KeyFrame::SetPose(const cv::Mat &Tcw_)
71 {
72  unique_lock<mutex> lock(mMutexPose);
73  Tcw_.copyTo(Tcw);
74  cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3);
75  cv::Mat tcw = Tcw.rowRange(0,3).col(3);
76  cv::Mat Rwc = Rcw.t();
77  Ow = -Rwc*tcw;
78 
79  Twc = cv::Mat::eye(4,4,Tcw.type());
80  Rwc.copyTo(Twc.rowRange(0,3).colRange(0,3));
81  Ow.copyTo(Twc.rowRange(0,3).col(3));
82  cv::Mat center = (cv::Mat_<float>(4,1) << mHalfBaseline, 0 , 0, 1);
83  Cw = Twc*center;
84 }
85 
87 {
88  unique_lock<mutex> lock(mMutexPose);
89  return Tcw.clone();
90 }
91 
93 {
94  unique_lock<mutex> lock(mMutexPose);
95  return Twc.clone();
96 }
97 
99 {
100  unique_lock<mutex> lock(mMutexPose);
101  return Ow.clone();
102 }
103 
105 {
106  unique_lock<mutex> lock(mMutexPose);
107  return Cw.clone();
108 }
109 
110 
112 {
113  unique_lock<mutex> lock(mMutexPose);
114  return Tcw.rowRange(0,3).colRange(0,3).clone();
115 }
116 
118 {
119  unique_lock<mutex> lock(mMutexPose);
120  return Tcw.rowRange(0,3).col(3).clone();
121 }
122 
123 void KeyFrame::AddConnection(KeyFrame *pKF, const int &weight)
124 {
125  {
126  unique_lock<mutex> lock(mMutexConnections);
127  if(!mConnectedKeyFrameWeights.count(pKF))
128  mConnectedKeyFrameWeights[pKF]=weight;
129  else if(mConnectedKeyFrameWeights[pKF]!=weight)
130  mConnectedKeyFrameWeights[pKF]=weight;
131  else
132  return;
133  }
134 
136 }
137 
139 {
140  unique_lock<mutex> lock(mMutexConnections);
141  vector<pair<int,KeyFrame*> > vPairs;
142  vPairs.reserve(mConnectedKeyFrameWeights.size());
143  for(map<KeyFrame*,int>::iterator mit=mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++)
144  vPairs.push_back(make_pair(mit->second,mit->first));
145 
146  sort(vPairs.begin(),vPairs.end());
147  list<KeyFrame*> lKFs;
148  list<int> lWs;
149  for(size_t i=0, iend=vPairs.size(); i<iend;i++)
150  {
151  lKFs.push_front(vPairs[i].second);
152  lWs.push_front(vPairs[i].first);
153  }
154 
155  mvpOrderedConnectedKeyFrames = vector<KeyFrame*>(lKFs.begin(),lKFs.end());
156  mvOrderedWeights = vector<int>(lWs.begin(), lWs.end());
157 }
158 
160 {
161  unique_lock<mutex> lock(mMutexConnections);
162  set<KeyFrame*> s;
163  for(map<KeyFrame*,int>::iterator mit=mConnectedKeyFrameWeights.begin();mit!=mConnectedKeyFrameWeights.end();mit++)
164  s.insert(mit->first);
165  return s;
166 }
167 
169 {
170  unique_lock<mutex> lock(mMutexConnections);
172 }
173 
174 vector<KeyFrame*> KeyFrame::GetBestCovisibilityKeyFrames(const int &N)
175 {
176  unique_lock<mutex> lock(mMutexConnections);
177  if((int)mvpOrderedConnectedKeyFrames.size()<N)
179  else
180  return vector<KeyFrame*>(mvpOrderedConnectedKeyFrames.begin(),mvpOrderedConnectedKeyFrames.begin()+N);
181 
182 }
183 
184 vector<KeyFrame*> KeyFrame::GetCovisiblesByWeight(const int &w)
185 {
186  unique_lock<mutex> lock(mMutexConnections);
187 
188  if(mvpOrderedConnectedKeyFrames.empty())
189  return vector<KeyFrame*>();
190 
191  vector<int>::iterator it = upper_bound(mvOrderedWeights.begin(),mvOrderedWeights.end(),w,KeyFrame::weightComp);
192  if(it==mvOrderedWeights.end())
193  return vector<KeyFrame*>();
194  else
195  {
196  int n = it-mvOrderedWeights.begin();
197  return vector<KeyFrame*>(mvpOrderedConnectedKeyFrames.begin(), mvpOrderedConnectedKeyFrames.begin()+n);
198  }
199 }
200 
202 {
203  unique_lock<mutex> lock(mMutexConnections);
204  if(mConnectedKeyFrameWeights.count(pKF))
205  return mConnectedKeyFrameWeights[pKF];
206  else
207  return 0;
208 }
209 
210 void KeyFrame::AddMapPoint(MapPoint *pMP, const size_t &idx)
211 {
212  unique_lock<mutex> lock(mMutexFeatures);
213  mvpMapPoints[idx]=pMP;
214 }
215 
216 void KeyFrame::EraseMapPointMatch(const size_t &idx)
217 {
218  unique_lock<mutex> lock(mMutexFeatures);
219  mvpMapPoints[idx]=static_cast<MapPoint*>(NULL);
220 }
221 
223 {
224  int idx = pMP->GetIndexInKeyFrame(this);
225  if(idx>=0)
226  mvpMapPoints[idx]=static_cast<MapPoint*>(NULL);
227 }
228 
229 
230 void KeyFrame::ReplaceMapPointMatch(const size_t &idx, MapPoint* pMP)
231 {
232  mvpMapPoints[idx]=pMP;
233 }
234 
235 set<MapPoint*> KeyFrame::GetMapPoints()
236 {
237  unique_lock<mutex> lock(mMutexFeatures);
238  set<MapPoint*> s;
239  for(size_t i=0, iend=mvpMapPoints.size(); i<iend; i++)
240  {
241  if(!mvpMapPoints[i])
242  continue;
243  MapPoint* pMP = mvpMapPoints[i];
244  if(!pMP->isBad())
245  s.insert(pMP);
246  }
247  return s;
248 }
249 
250 int KeyFrame::TrackedMapPoints(const int &minObs)
251 {
252  unique_lock<mutex> lock(mMutexFeatures);
253 
254  int nPoints=0;
255  const bool bCheckObs = minObs>0;
256  for(int i=0; i<N; i++)
257  {
258  MapPoint* pMP = mvpMapPoints[i];
259  if(pMP)
260  {
261  if(!pMP->isBad())
262  {
263  if(bCheckObs)
264  {
265  if(mvpMapPoints[i]->Observations()>=minObs)
266  nPoints++;
267  }
268  else
269  nPoints++;
270  }
271  }
272  }
273 
274  return nPoints;
275 }
276 
277 vector<MapPoint*> KeyFrame::GetMapPointMatches()
278 {
279  unique_lock<mutex> lock(mMutexFeatures);
280  return mvpMapPoints;
281 }
282 
283 MapPoint* KeyFrame::GetMapPoint(const size_t &idx)
284 {
285  unique_lock<mutex> lock(mMutexFeatures);
286  return mvpMapPoints[idx];
287 }
288 
290 {
291  map<KeyFrame*,int> KFcounter;
292 
293  vector<MapPoint*> vpMP;
294 
295  {
296  unique_lock<mutex> lockMPs(mMutexFeatures);
297  vpMP = mvpMapPoints;
298  }
299 
300  //For all map points in keyframe check in which other keyframes are they seen
301  //Increase counter for those keyframes
302  for(vector<MapPoint*>::iterator vit=vpMP.begin(), vend=vpMP.end(); vit!=vend; vit++)
303  {
304  MapPoint* pMP = *vit;
305 
306  if(!pMP)
307  continue;
308 
309  if(pMP->isBad())
310  continue;
311 
312  map<KeyFrame*,size_t> observations = pMP->GetObservations();
313 
314  for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
315  {
316  if(mit->first->mnId==mnId)
317  continue;
318  KFcounter[mit->first]++;
319  }
320  }
321 
322  // This should not happen
323  if(KFcounter.empty())
324  return;
325 
326  //If the counter is greater than threshold add connection
327  //In case no keyframe counter is over threshold add the one with maximum counter
328  int nmax=0;
329  KeyFrame* pKFmax=NULL;
330  int th = 15;
331 
332  vector<pair<int,KeyFrame*> > vPairs;
333  vPairs.reserve(KFcounter.size());
334  for(map<KeyFrame*,int>::iterator mit=KFcounter.begin(), mend=KFcounter.end(); mit!=mend; mit++)
335  {
336  if(mit->second>nmax)
337  {
338  nmax=mit->second;
339  pKFmax=mit->first;
340  }
341  if(mit->second>=th)
342  {
343  vPairs.push_back(make_pair(mit->second,mit->first));
344  (mit->first)->AddConnection(this,mit->second);
345  }
346  }
347 
348  if(vPairs.empty())
349  {
350  vPairs.push_back(make_pair(nmax,pKFmax));
351  pKFmax->AddConnection(this,nmax);
352  }
353 
354  sort(vPairs.begin(),vPairs.end());
355  list<KeyFrame*> lKFs;
356  list<int> lWs;
357  for(size_t i=0; i<vPairs.size();i++)
358  {
359  lKFs.push_front(vPairs[i].second);
360  lWs.push_front(vPairs[i].first);
361  }
362 
363  {
364  unique_lock<mutex> lockCon(mMutexConnections);
365 
366  // mspConnectedKeyFrames = spConnectedKeyFrames;
367  mConnectedKeyFrameWeights = KFcounter;
368  mvpOrderedConnectedKeyFrames = vector<KeyFrame*>(lKFs.begin(),lKFs.end());
369  mvOrderedWeights = vector<int>(lWs.begin(), lWs.end());
370 
371  if(mbFirstConnection && mnId!=0)
372  {
374  mpParent->AddChild(this);
375  mbFirstConnection = false;
376  }
377 
378  }
379 }
380 
382 {
383  unique_lock<mutex> lockCon(mMutexConnections);
384  mspChildrens.insert(pKF);
385 }
386 
388 {
389  unique_lock<mutex> lockCon(mMutexConnections);
390  mspChildrens.erase(pKF);
391 }
392 
394 {
395  unique_lock<mutex> lockCon(mMutexConnections);
396  mpParent = pKF;
397  pKF->AddChild(this);
398 }
399 
400 set<KeyFrame*> KeyFrame::GetChilds()
401 {
402  unique_lock<mutex> lockCon(mMutexConnections);
403  return mspChildrens;
404 }
405 
407 {
408  unique_lock<mutex> lockCon(mMutexConnections);
409  return mpParent;
410 }
411 
413 {
414  unique_lock<mutex> lockCon(mMutexConnections);
415  return mspChildrens.count(pKF);
416 }
417 
419 {
420  unique_lock<mutex> lockCon(mMutexConnections);
421  mbNotErase = true;
422  mspLoopEdges.insert(pKF);
423 }
424 
425 set<KeyFrame*> KeyFrame::GetLoopEdges()
426 {
427  unique_lock<mutex> lockCon(mMutexConnections);
428  return mspLoopEdges;
429 }
430 
432 {
433  unique_lock<mutex> lock(mMutexConnections);
434  mbNotErase = true;
435 }
436 
438 {
439  {
440  unique_lock<mutex> lock(mMutexConnections);
441  if(mspLoopEdges.empty())
442  {
443  mbNotErase = false;
444  }
445  }
446 
447  if(mbToBeErased)
448  {
449  SetBadFlag();
450  }
451 }
452 
454 {
455  {
456  unique_lock<mutex> lock(mMutexConnections);
457  if(mnId==0)
458  return;
459  else if(mbNotErase)
460  {
461  mbToBeErased = true;
462  return;
463  }
464  }
465 
466  for(map<KeyFrame*,int>::iterator mit = mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++)
467  mit->first->EraseConnection(this);
468 
469  for(size_t i=0; i<mvpMapPoints.size(); i++)
470  if(mvpMapPoints[i])
471  mvpMapPoints[i]->EraseObservation(this);
472  {
473  unique_lock<mutex> lock(mMutexConnections);
474  unique_lock<mutex> lock1(mMutexFeatures);
475 
478 
479  // Update Spanning Tree
480  set<KeyFrame*> sParentCandidates;
481  sParentCandidates.insert(mpParent);
482 
483  // Assign at each iteration one children with a parent (the pair with highest covisibility weight)
484  // Include that children as new parent candidate for the rest
485  while(!mspChildrens.empty())
486  {
487  bool bContinue = false;
488 
489  int max = -1;
490  KeyFrame* pC;
491  KeyFrame* pP;
492 
493  for(set<KeyFrame*>::iterator sit=mspChildrens.begin(), send=mspChildrens.end(); sit!=send; sit++)
494  {
495  KeyFrame* pKF = *sit;
496  if(pKF->isBad())
497  continue;
498 
499  // Check if a parent candidate is connected to the keyframe
500  vector<KeyFrame*> vpConnected = pKF->GetVectorCovisibleKeyFrames();
501  for(size_t i=0, iend=vpConnected.size(); i<iend; i++)
502  {
503  for(set<KeyFrame*>::iterator spcit=sParentCandidates.begin(), spcend=sParentCandidates.end(); spcit!=spcend; spcit++)
504  {
505  if(vpConnected[i]->mnId == (*spcit)->mnId)
506  {
507  int w = pKF->GetWeight(vpConnected[i]);
508  if(w>max)
509  {
510  pC = pKF;
511  pP = vpConnected[i];
512  max = w;
513  bContinue = true;
514  }
515  }
516  }
517  }
518  }
519 
520  if(bContinue)
521  {
522  pC->ChangeParent(pP);
523  sParentCandidates.insert(pC);
524  mspChildrens.erase(pC);
525  }
526  else
527  break;
528  }
529 
530  // If a children has no covisibility links with any parent candidate, assign to the original parent of this KF
531  if(!mspChildrens.empty())
532  for(set<KeyFrame*>::iterator sit=mspChildrens.begin(); sit!=mspChildrens.end(); sit++)
533  {
534  (*sit)->ChangeParent(mpParent);
535  }
536 
537  mpParent->EraseChild(this);
539  mbBad = true;
540  }
541 
542 
543  mpMap->EraseKeyFrame(this);
544  mpKeyFrameDB->erase(this);
545 }
546 
548 {
549  unique_lock<mutex> lock(mMutexConnections);
550  return mbBad;
551 }
552 
554 {
555  bool bUpdate = false;
556  {
557  unique_lock<mutex> lock(mMutexConnections);
558  if(mConnectedKeyFrameWeights.count(pKF))
559  {
560  mConnectedKeyFrameWeights.erase(pKF);
561  bUpdate=true;
562  }
563  }
564 
565  if(bUpdate)
567 }
568 
569 vector<size_t> KeyFrame::GetFeaturesInArea(const float &x, const float &y, const float &r) const
570 {
571  vector<size_t> vIndices;
572  vIndices.reserve(N);
573 
574  const int nMinCellX = max(0,(int)floor((x-mnMinX-r)*mfGridElementWidthInv));
575  if(nMinCellX>=mnGridCols)
576  return vIndices;
577 
578  const int nMaxCellX = min((int)mnGridCols-1,(int)ceil((x-mnMinX+r)*mfGridElementWidthInv));
579  if(nMaxCellX<0)
580  return vIndices;
581 
582  const int nMinCellY = max(0,(int)floor((y-mnMinY-r)*mfGridElementHeightInv));
583  if(nMinCellY>=mnGridRows)
584  return vIndices;
585 
586  const int nMaxCellY = min((int)mnGridRows-1,(int)ceil((y-mnMinY+r)*mfGridElementHeightInv));
587  if(nMaxCellY<0)
588  return vIndices;
589 
590  for(int ix = nMinCellX; ix<=nMaxCellX; ix++)
591  {
592  for(int iy = nMinCellY; iy<=nMaxCellY; iy++)
593  {
594  const vector<size_t> vCell = mGrid[ix][iy];
595  for(size_t j=0, jend=vCell.size(); j<jend; j++)
596  {
597  const cv::KeyPoint &kpUn = mvKeysUn[vCell[j]];
598  const float distx = kpUn.pt.x-x;
599  const float disty = kpUn.pt.y-y;
600 
601  if(fabs(distx)<r && fabs(disty)<r)
602  vIndices.push_back(vCell[j]);
603  }
604  }
605  }
606 
607  return vIndices;
608 }
609 
610 bool KeyFrame::IsInImage(const float &x, const float &y) const
611 {
612  return (x>=mnMinX && x<mnMaxX && y>=mnMinY && y<mnMaxY);
613 }
614 
616 {
617  const float z = mvDepth[i];
618  if(z>0)
619  {
620  const float u = mvKeys[i].pt.x;
621  const float v = mvKeys[i].pt.y;
622  const float x = (u-cx)*z*invfx;
623  const float y = (v-cy)*z*invfy;
624  cv::Mat x3Dc = (cv::Mat_<float>(3,1) << x, y, z);
625 
626  unique_lock<mutex> lock(mMutexPose);
627  return Twc.rowRange(0,3).colRange(0,3)*x3Dc+Twc.rowRange(0,3).col(3);
628  }
629  else
630  return cv::Mat();
631 }
632 
634 {
635  vector<MapPoint*> vpMapPoints;
636  cv::Mat Tcw_;
637  {
638  unique_lock<mutex> lock(mMutexFeatures);
639  unique_lock<mutex> lock2(mMutexPose);
640  vpMapPoints = mvpMapPoints;
641  Tcw_ = Tcw.clone();
642  }
643 
644  vector<float> vDepths;
645  vDepths.reserve(N);
646  cv::Mat Rcw2 = Tcw_.row(2).colRange(0,3);
647  Rcw2 = Rcw2.t();
648  float zcw = Tcw_.at<float>(2,3);
649  for(int i=0; i<N; i++)
650  {
651  if(mvpMapPoints[i])
652  {
653  MapPoint* pMP = mvpMapPoints[i];
654  cv::Mat x3Dw = pMP->GetWorldPos();
655  float z = Rcw2.dot(x3Dw)+zcw;
656  vDepths.push_back(z);
657  }
658  }
659 
660  sort(vDepths.begin(),vDepths.end());
661 
662  return vDepths[(vDepths.size()-1)/q];
663 }
664 
665 // map serialization addition
666 // Default serializing Constructor
672  fx(0.0), fy(0.0), cx(0.0), cy(0.0), invfx(0.0), invfy(0.0),
673  mbf(0.0), mb(0.0), mThDepth(0.0), N(0), mnScaleLevels(0), mfScaleFactor(0),
674  mfLogScaleFactor(0.0),
675  mnMinX(0), mnMinY(0), mnMaxX(0),
676  mnMaxY(0)
677 {}
678 template<class Archive>
679 void KeyFrame::serialize(Archive &ar, const unsigned int version)
680 {
681  // no mutex needed vars
682  ar & nNextId;
683  ar & mnId;
684  ar & const_cast<long unsigned int &>(mnFrameId);
685  ar & const_cast<double &>(mTimeStamp);
686  // Grid related vars
687  ar & const_cast<int &>(mnGridCols);
688  ar & const_cast<int &>(mnGridRows);
689  ar & const_cast<float &>(mfGridElementWidthInv);
690  ar & const_cast<float &>(mfGridElementHeightInv);
691  // Tracking related vars
693  // LocalMaping related vars
695  // KeyFrameDB related vars
697  // LoopClosing related vars
699  // calibration parameters
700  ar & const_cast<float &>(fx) & const_cast<float &>(fy) & const_cast<float &>(cx) & const_cast<float &>(cy);
701  ar & const_cast<float &>(invfx) & const_cast<float &>(invfy) & const_cast<float &>(mbf);
702  ar & const_cast<float &>(mb) & const_cast<float &>(mThDepth);
703  // Number of KeyPoints;
704  ar & const_cast<int &>(N);
705  // KeyPoints, stereo coordinate and descriptors
706  ar & const_cast<std::vector<cv::KeyPoint> &>(mvKeys);
707  ar & const_cast<std::vector<cv::KeyPoint> &>(mvKeysUn);
708  ar & const_cast<std::vector<float> &>(mvuRight);
709  ar & const_cast<std::vector<float> &>(mvDepth);
710  ar & const_cast<cv::Mat &>(mDescriptors);
711  // Bow
712  ar & mBowVec & mFeatVec;
713  // Pose relative to parent
714  ar & mTcp;
715  // Scale related
716  ar & const_cast<int &>(mnScaleLevels) & const_cast<float &>(mfScaleFactor) & const_cast<float &>(mfLogScaleFactor);
717  ar & const_cast<std::vector<float> &>(mvScaleFactors) & const_cast<std::vector<float> &>(mvLevelSigma2) & const_cast<std::vector<float> &>(mvInvLevelSigma2);
718  // Image bounds and calibration
719  ar & const_cast<int &>(mnMinX) & const_cast<int &>(mnMinY) & const_cast<int &>(mnMaxX) & const_cast<int &>(mnMaxY);
720  ar & const_cast<cv::Mat &>(mK);
721 
722  // mutex needed vars, but don't lock mutex in the save/load procedure
723  {
724  unique_lock<mutex> lock_pose(mMutexPose);
725  ar & Tcw & Twc & Ow & Cw;
726  }
727  {
728  unique_lock<mutex> lock_feature(mMutexFeatures);
729  ar & mvpMapPoints; // hope boost deal with the pointer graph well
730  }
731  // BoW
732  ar & mpKeyFrameDB;
733  // mpORBvocabulary restore elsewhere(see SetORBvocab)
734  {
735  // Grid related
736  unique_lock<mutex> lock_connection(mMutexConnections);
738  // Spanning Tree and Loop Edges
740  // Bad flags
742  }
743  // Map Points
744  ar & mpMap;
745  // don't save mutex
746 }
747 template void KeyFrame::serialize(boost::archive::binary_iarchive&, const unsigned int);
748 template void KeyFrame::serialize(boost::archive::binary_oarchive&, const unsigned int);
749 
750 } //namespace ORB_SLAM
std::vector< KeyFrame * > GetBestCovisibilityKeyFrames(const int &N)
Definition: KeyFrame.cc:174
const int mnMinY
Definition: KeyFrame.h:187
const int mnMaxX
Definition: KeyFrame.h:188
cv::Mat GetPoseInverse()
Definition: KeyFrame.cc:92
cv::Mat GetRotation()
Definition: KeyFrame.cc:111
void serialize(Archive &ar, const unsigned int version)
Definition: KeyFrame.cc:679
void EraseMapPointMatch(const size_t &idx)
Definition: KeyFrame.cc:216
const std::vector< cv::KeyPoint > mvKeysUn
Definition: KeyFrame.h:165
cv::Mat GetCameraCenter()
Definition: KeyFrame.cc:98
const float invfx
Definition: KeyFrame.h:158
std::set< KeyFrame * > GetConnectedKeyFrames()
Definition: KeyFrame.cc:159
const std::vector< float > mvScaleFactors
Definition: KeyFrame.h:181
std::set< KeyFrame * > mspChildrens
Definition: KeyFrame.h:220
const float mbf
Definition: KeyFrame.h:158
long unsigned int mnTrackReferenceForFrame
Definition: KeyFrame.h:137
#define FRAME_GRID_COLS
Definition: Frame.h:38
std::mutex mMutexFeatures
Definition: KeyFrame.h:234
const float mfScaleFactor
Definition: KeyFrame.h:179
cv::Mat GetPose()
Definition: KeyFrame.cc:86
void AddMapPoint(MapPoint *pMP, const size_t &idx)
Definition: KeyFrame.cc:210
cv::Mat UnprojectStereo(int i)
Definition: KeyFrame.cc:615
const std::vector< float > mvLevelSigma2
Definition: KeyFrame.h:182
XmlRpcServer s
const double mTimeStamp
Definition: KeyFrame.h:128
const float mThDepth
Definition: KeyFrame.h:158
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
void ReplaceMapPointMatch(const size_t &idx, MapPoint *pMP)
Definition: KeyFrame.cc:230
long unsigned int mnBAGlobalForKF
Definition: KeyFrame.h:155
std::vector< MapPoint * > GetMapPointMatches()
Definition: KeyFrame.cc:277
const float invfy
Definition: KeyFrame.h:158
long unsigned int mnLoopQuery
Definition: KeyFrame.h:145
std::vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r) const
Definition: KeyFrame.cc:569
long unsigned int mnRelocQuery
Definition: KeyFrame.h:148
TFSIMD_FORCE_INLINE const tfScalar & y() const
int TrackedMapPoints(const int &minObs)
Definition: KeyFrame.cc:250
void EraseChild(KeyFrame *pKF)
Definition: KeyFrame.cc:387
std::vector< std::size_t > mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]
Definition: Frame.h:161
const int mnMaxY
Definition: KeyFrame.h:189
const cv::Mat mK
Definition: KeyFrame.h:190
void EraseConnection(KeyFrame *pKF)
Definition: KeyFrame.cc:553
cv::Mat GetStereoCenter()
Definition: KeyFrame.cc:104
const float cx
Definition: KeyFrame.h:158
const std::vector< float > mvInvLevelSigma2
Definition: KeyFrame.h:183
virtual void transform(const std::vector< TDescriptor > &features, BowVector &v) const
std::map< KeyFrame *, size_t > GetObservations()
Definition: MapPoint.cc:139
DBoW2::BowVector mBowVec
Definition: KeyFrame.h:171
cv::Mat mTcwBefGBA
Definition: KeyFrame.h:154
std::vector< KeyFrame * > mvpOrderedConnectedKeyFrames
Definition: KeyFrame.h:214
void ChangeParent(KeyFrame *pKF)
Definition: KeyFrame.cc:393
const float fx
Definition: KeyFrame.h:158
long unsigned int mnBAFixedForKF
Definition: KeyFrame.h:142
std::vector< std::vector< std::vector< size_t > > > mGrid
Definition: KeyFrame.h:211
cv::Mat GetTranslation()
Definition: KeyFrame.cc:117
const std::vector< float > mvDepth
Definition: KeyFrame.h:167
KeyFrame * mpParent
Definition: KeyFrame.h:219
cv::Mat mTcw
Definition: Frame.h:164
const int mnScaleLevels
Definition: KeyFrame.h:178
#define FRAME_GRID_ROWS
Definition: Frame.h:37
ORBVocabulary * mpORBvocabulary
Definition: KeyFrame.h:208
int GetWeight(KeyFrame *pKF)
Definition: KeyFrame.cc:201
bool IsInImage(const float &x, const float &y) const
Definition: KeyFrame.cc:610
std::mutex mMutexPose
Definition: KeyFrame.h:232
static std::vector< cv::Mat > toDescriptorVector(const cv::Mat &Descriptors)
Definition: Converter.cc:27
TFSIMD_FORCE_INLINE const tfScalar & x() const
long unsigned int mnFuseTargetForKF
Definition: KeyFrame.h:138
std::set< KeyFrame * > mspLoopEdges
Definition: KeyFrame.h:221
std::vector< int > mvOrderedWeights
Definition: KeyFrame.h:215
const float mfGridElementHeightInv
Definition: KeyFrame.h:134
MapPoint * GetMapPoint(const size_t &idx)
Definition: KeyFrame.cc:283
std::vector< MapPoint * > mvpMapPoints
Definition: KeyFrame.h:204
const float cy
Definition: KeyFrame.h:158
float ComputeSceneMedianDepth(const int q)
Definition: KeyFrame.cc:633
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
TFSIMD_FORCE_INLINE const tfScalar & z() const
void EraseKeyFrame(KeyFrame *pKF)
Definition: Map.cc:55
void AddLoopEdge(KeyFrame *pKF)
Definition: KeyFrame.cc:418
bool hasChild(KeyFrame *pKF)
Definition: KeyFrame.cc:412
TFSIMD_FORCE_INLINE const tfScalar & w() const
const int mnMinX
Definition: KeyFrame.h:186
const std::vector< cv::KeyPoint > mvKeys
Definition: KeyFrame.h:164
std::set< KeyFrame * > GetChilds()
Definition: KeyFrame.cc:400
int min(int a, int b)
DBoW2::FeatureVector mFeatVec
Definition: KeyFrame.h:172
const float fy
Definition: KeyFrame.h:158
static long unsigned int nNextId
Definition: KeyFrame.h:124
const std::vector< float > mvuRight
Definition: KeyFrame.h:166
int GetIndexInKeyFrame(KeyFrame *pKF)
Definition: MapPoint.cc:315
void AddConnection(KeyFrame *pKF, const int &weight)
Definition: KeyFrame.cc:123
std::set< MapPoint * > GetMapPoints()
Definition: KeyFrame.cc:235
static bool weightComp(int a, int b)
Definition: KeyFrame.h:112
void UpdateBestCovisibles()
Definition: KeyFrame.cc:138
const float mb
Definition: KeyFrame.h:158
const long unsigned int mnFrameId
Definition: KeyFrame.h:126
void AddChild(KeyFrame *pKF)
Definition: KeyFrame.cc:381
std::mutex mMutexConnections
Definition: KeyFrame.h:233
std::map< KeyFrame *, int > mConnectedKeyFrameWeights
Definition: KeyFrame.h:213
KeyFrameDatabase * mpKeyFrameDB
Definition: KeyFrame.h:207
const int mnGridCols
Definition: KeyFrame.h:131
void UpdateConnections()
Definition: KeyFrame.cc:289
long unsigned int mnId
Definition: KeyFrame.h:125
KeyFrame * GetParent()
Definition: KeyFrame.cc:406
const cv::Mat mDescriptors
Definition: KeyFrame.h:168
const float mfGridElementWidthInv
Definition: KeyFrame.h:133
const float mfLogScaleFactor
Definition: KeyFrame.h:180
const int mnGridRows
Definition: KeyFrame.h:132


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