SLProject  4.2.000
A platform independent 3D computer graphics framework for desktop OS, Android, iOS and online in web browsers
WAIKeyFrameDB Class Reference

AR Keyframe database class. More...

#include <WAIKeyFrameDB.h>

Public Types

enum  LoopDetectionErrorCodes { LOOP_DETECTION_ERROR_NONE , LOOP_DETECTION_ERROR_NO_CANDIDATES_WITH_COMMON_WORDS , LOOP_DETECTION_ERROR_NO_SIMILAR_CANDIDATES }
 

Public Member Functions

 WAIKeyFrameDB (WAIOrbVocabulary *voc)
 
void add (WAIKeyFrame *pKF)
 
void erase (WAIKeyFrame *pKF)
 
void clear ()
 
std::vector< std::list< WAIKeyFrame * > > & getInvertedFile ()
 
std::vector< WAIKeyFrame * > DetectLoopCandidates (WAIKeyFrame *pKF, float minCommonWordFactor, float minScore, int *errorCode)
 
std::vector< WAIKeyFrame * > DetectRelocalizationCandidates (WAIFrame *F, float minCommonWordFactor, bool applyMinAccScoreFilter=false)
 
std::vector< WAIKeyFrame * > DetectRelocalizationCandidates (WAIFrame *F, cv::Mat extrinsicGuess)
 

Protected Attributes

WAIOrbVocabularympVoc
 
std::vector< std::list< WAIKeyFrame * > > mvInvertedFile
 
std::mutex mMutex
 

Detailed Description

AR Keyframe database class.

This file is part of ORB-SLAM2.

Copyright (C) 2014-2016 Ra�l Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) For more information see https://github.com/raulmur/ORB_SLAM2

ORB-SLAM2 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.

ORB-SLAM2 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with ORB-SLAM2. If not, see http://www.gnu.org/licenses/.

Definition at line 45 of file WAIKeyFrameDB.h.

Member Enumeration Documentation

◆ LoopDetectionErrorCodes

Enumerator
LOOP_DETECTION_ERROR_NONE 
LOOP_DETECTION_ERROR_NO_CANDIDATES_WITH_COMMON_WORDS 
LOOP_DETECTION_ERROR_NO_SIMILAR_CANDIDATES 

Definition at line 58 of file WAIKeyFrameDB.h.

Constructor & Destructor Documentation

◆ WAIKeyFrameDB()

WAIKeyFrameDB::WAIKeyFrameDB ( WAIOrbVocabulary voc)

This file is part of ORB-SLAM2.

Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) For more information see https://github.com/raulmur/ORB_SLAM2

ORB-SLAM2 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.

ORB-SLAM2 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.

You should have received a copy of the GNU General Public License along with ORB-SLAM2. If not, see http://www.gnu.org/licenses/.

Definition at line 34 of file WAIKeyFrameDB.cpp.

34  : mpVoc(voc)
35 {
36  mvInvertedFile.resize(mpVoc->size());
37 }
WAIOrbVocabulary * mpVoc
Definition: WAIKeyFrameDB.h:72
std::vector< std::list< WAIKeyFrame * > > mvInvertedFile
Definition: WAIKeyFrameDB.h:74

Member Function Documentation

◆ add()

void WAIKeyFrameDB::add ( WAIKeyFrame pKF)

Definition at line 40 of file WAIKeyFrameDB.cpp.

41 {
42  std::unique_lock<std::mutex> lock(mMutex);
43  if (pKF->mBowVec.data.empty())
44  {
45  std::cout << "kf data empty" << std::endl;
46  return;
47  }
48  for (auto vit = pKF->mBowVec.getWordScoreMapping().begin(), vend = pKF->mBowVec.getWordScoreMapping().end(); vit != vend; vit++)
49  {
50  mvInvertedFile[vit->first].push_back(pKF);
51  }
52 }
std::mutex mMutex
Definition: WAIKeyFrameDB.h:77
WAIBowVector mBowVec
Definition: WAIKeyFrame.h:226
fbow::fBow & getWordScoreMapping()
fbow::fBow data

◆ clear()

void WAIKeyFrameDB::clear ( )

Definition at line 75 of file WAIKeyFrameDB.cpp.

76 {
77  mvInvertedFile.clear();
78  mvInvertedFile.resize(mpVoc->size());
79 }

◆ DetectLoopCandidates()

std::vector< WAIKeyFrame * > WAIKeyFrameDB::DetectLoopCandidates ( WAIKeyFrame pKF,
float  minCommonWordFactor,
float  minScore,
int *  errorCode 
)

Definition at line 85 of file WAIKeyFrameDB.cpp.

86 {
87  std::set<WAIKeyFrame*> spConnectedKeyFrames = pKF->GetConnectedKeyFrames();
88  std::list<WAIKeyFrame*> lKFsSharingWords;
89 
90  // Search all keyframes that share a word with current keyframes
91  // Discard keyframes connected to the query keyframe
92  {
93  std::unique_lock<std::mutex> lock(mMutex);
94 
95  for (auto vit = pKF->mBowVec.getWordScoreMapping().begin(), vend = pKF->mBowVec.getWordScoreMapping().end(); vit != vend; vit++)
96  {
97  std::list<WAIKeyFrame*>& lKFs = mvInvertedFile[vit->first];
98 
99  for (std::list<WAIKeyFrame*>::iterator lit = lKFs.begin(), lend = lKFs.end(); lit != lend; lit++)
100  {
101  WAIKeyFrame* pKFi = *lit;
102  if (pKFi->mnLoopQuery != pKF->mnId)
103  {
104  pKFi->mnLoopWords = 0;
105  if (!spConnectedKeyFrames.count(pKFi))
106  {
107  pKFi->mnLoopQuery = pKF->mnId;
108  lKFsSharingWords.push_back(pKFi);
109  }
110  }
111  pKFi->mnLoopWords++;
112  }
113  }
114  }
115 
116  if (lKFsSharingWords.empty())
117  {
119  return std::vector<WAIKeyFrame*>();
120  }
121 
122  std::list<std::pair<float, WAIKeyFrame*>> lScoreAndMatch;
123 
124  // Only compare against those keyframes that share enough words
125  int maxCommonWords = 0;
126  for (std::list<WAIKeyFrame*>::iterator lit = lKFsSharingWords.begin(), lend = lKFsSharingWords.end(); lit != lend; lit++)
127  {
128  if ((*lit)->mnLoopWords > maxCommonWords)
129  maxCommonWords = (*lit)->mnLoopWords;
130  }
131 
132  int minCommonWords = (int)(maxCommonWords * minCommonWordFactor);
133 
134  // Compute similarity score. Retain the matches whose score is higher than minScore
135  for (std::list<WAIKeyFrame*>::iterator lit = lKFsSharingWords.begin(), lend = lKFsSharingWords.end(); lit != lend; lit++)
136  {
137  WAIKeyFrame* pKFi = *lit;
138 
139  if (pKFi->mnLoopWords > minCommonWords)
140  {
141  float si = (float)mpVoc->score(pKF->mBowVec, pKFi->mBowVec);
142 
143  pKFi->mLoopScore = si;
144  if (si >= minScore)
145  lScoreAndMatch.push_back(std::make_pair(si, pKFi));
146  }
147  }
148 
149  if (lScoreAndMatch.empty())
150  {
152  return std::vector<WAIKeyFrame*>();
153  }
154 
155  std::list<std::pair<float, WAIKeyFrame*>> lAccScoreAndMatch;
156  float bestAccScore = minScore;
157 
158  // Lets now accumulate score by covisibility
159  for (std::list<std::pair<float, WAIKeyFrame*>>::iterator it = lScoreAndMatch.begin(), itend = lScoreAndMatch.end(); it != itend; it++)
160  {
161  WAIKeyFrame* pKFi = it->second;
162  std::vector<WAIKeyFrame*> vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10);
163 
164  float bestScore = it->first;
165  float accScore = it->first;
166  WAIKeyFrame* pBestKF = pKFi;
167  for (std::vector<WAIKeyFrame*>::iterator vit = vpNeighs.begin(), vend = vpNeighs.end(); vit != vend; vit++)
168  {
169  WAIKeyFrame* pKF2 = *vit;
170  if (pKF2->mnLoopQuery == pKF->mnId && pKF2->mnLoopWords > minCommonWords)
171  {
172  accScore += pKF2->mLoopScore;
173  if (pKF2->mLoopScore > bestScore)
174  {
175  pBestKF = pKF2;
176  bestScore = pKF2->mLoopScore;
177  }
178  }
179  }
180 
181  lAccScoreAndMatch.push_back(std::make_pair(accScore, pBestKF));
182  if (accScore > bestAccScore)
183  bestAccScore = accScore;
184  }
185 
186  // Return all those keyframes with a score higher than 0.75*bestScore
187  float minScoreToRetain = 0.75f * bestAccScore;
188 
189  std::set<WAIKeyFrame*> spAlreadyAddedKF;
190  std::vector<WAIKeyFrame*> vpLoopCandidates;
191  vpLoopCandidates.reserve(lAccScoreAndMatch.size());
192 
193  for (std::list<std::pair<float, WAIKeyFrame*>>::iterator it = lAccScoreAndMatch.begin(), itend = lAccScoreAndMatch.end(); it != itend; it++)
194  {
195  if (it->first > minScoreToRetain)
196  {
197  WAIKeyFrame* pKFi = it->second;
198  if (!spAlreadyAddedKF.count(pKFi))
199  {
200  vpLoopCandidates.push_back(pKFi);
201  spAlreadyAddedKF.insert(pKFi);
202  }
203  }
204  }
205 
206  *errorCode = LOOP_DETECTION_ERROR_NONE;
207  return vpLoopCandidates;
208 }
AR Keyframe node class.
Definition: WAIKeyFrame.h:60
std::vector< WAIKeyFrame * > GetBestCovisibilityKeyFrames(const int &N)
long unsigned int mnId
Definition: WAIKeyFrame.h:175
long unsigned int mnLoopQuery
Definition: WAIKeyFrame.h:202
float mLoopScore
Definition: WAIKeyFrame.h:204
std::set< WAIKeyFrame * > GetConnectedKeyFrames()
double score(WAIBowVector &bow1, WAIBowVector &bow2)

◆ DetectRelocalizationCandidates() [1/2]

std::vector< WAIKeyFrame * > WAIKeyFrameDB::DetectRelocalizationCandidates ( WAIFrame F,
cv::Mat  extrinsicGuess 
)

Definition at line 211 of file WAIKeyFrameDB.cpp.

212 {
213  std::list<WAIKeyFrame*> lKFsSharingWords;
214 
215  // Search all keyframes that share a word with current frame
216  {
217  std::unique_lock<std::mutex> lock(mMutex);
218 
219  for (auto vit = F->mBowVec.getWordScoreMapping().begin(), vend = F->mBowVec.getWordScoreMapping().end(); vit != vend; vit++)
220  {
221  if (vit->first > mvInvertedFile.size())
222  {
223  std::stringstream ss;
224  ss << "WAIKeyFrameDB::DetectRelocalizationCandidates: word index bigger than inverted file. word: " << vit->first << " val: " << vit->second;
225  throw std::runtime_error(ss.str());
226  }
227 
228  std::list<WAIKeyFrame*>& lKFs = mvInvertedFile[vit->first];
229 
230  for (std::list<WAIKeyFrame*>::iterator lit = lKFs.begin(), lend = lKFs.end(); lit != lend; lit++)
231  {
232  WAIKeyFrame* pKFi = *lit;
233  if (pKFi->isBad())
234  continue;
235 
236  if (pKFi->mnRelocQuery != F->mnId)
237  {
238  pKFi->mnRelocWords = 0;
239  pKFi->mRelocScore = 0.f;
240  pKFi->mnRelocQuery = F->mnId;
241  lKFsSharingWords.push_back(pKFi);
242  }
243  pKFi->mnRelocWords++;
244  }
245  }
246  }
247  if (lKFsSharingWords.empty())
248  return std::vector<WAIKeyFrame*>();
249 
250  std::vector<WAIKeyFrame*> kfs;
251  for (std::list<WAIKeyFrame*>::iterator lit = lKFsSharingWords.begin(), lend = lKFsSharingWords.end(); lit != lend; lit++)
252  {
253  kfs.push_back(*lit);
254  }
255  return kfs;
256 }
long unsigned int mnId
Definition: WAIFrame.h:159
WAIBowVector mBowVec
Definition: WAIFrame.h:137
float mRelocScore
Definition: WAIKeyFrame.h:207
int mnRelocWords
Definition: WAIKeyFrame.h:206
long unsigned int mnRelocQuery
Definition: WAIKeyFrame.h:205

◆ DetectRelocalizationCandidates() [2/2]

std::vector< WAIKeyFrame * > WAIKeyFrameDB::DetectRelocalizationCandidates ( WAIFrame F,
float  minCommonWordFactor,
bool  applyMinAccScoreFilter = false 
)

Definition at line 258 of file WAIKeyFrameDB.cpp.

259 {
260  std::list<WAIKeyFrame*> lKFsSharingWords;
261 
262  // Search all keyframes that share a word with current frame
263  {
264  std::unique_lock<std::mutex> lock(mMutex);
265 
266  for (auto vit = F->mBowVec.getWordScoreMapping().begin(), vend = F->mBowVec.getWordScoreMapping().end(); vit != vend; vit++)
267  {
268  if (vit->first > mvInvertedFile.size())
269  {
270  std::stringstream ss;
271  ss << "WAIKeyFrameDB::DetectRelocalizationCandidates: word index bigger than inverted file. word: " << vit->first << " val: " << vit->second;
272  throw std::runtime_error(ss.str());
273  }
274 
275  std::list<WAIKeyFrame*>& lKFs = mvInvertedFile[vit->first];
276 
277  for (std::list<WAIKeyFrame*>::iterator lit = lKFs.begin(), lend = lKFs.end(); lit != lend; lit++)
278  {
279  WAIKeyFrame* pKFi = *lit;
280  if (pKFi->isBad())
281  continue;
282 
283  if (pKFi->mnRelocQuery != F->mnId)
284  {
285  pKFi->mnRelocWords = 0;
286  pKFi->mRelocScore = 0.f;
287  pKFi->mnRelocQuery = F->mnId;
288  lKFsSharingWords.push_back(pKFi);
289  }
290  pKFi->mnRelocWords++;
291  }
292  }
293  }
294  if (lKFsSharingWords.empty())
295  return std::vector<WAIKeyFrame*>();
296 
297  // Only compare against those keyframes that share enough words
298  int maxCommonWords = 0;
299  for (std::list<WAIKeyFrame*>::iterator lit = lKFsSharingWords.begin(), lend = lKFsSharingWords.end(); lit != lend; lit++)
300  {
301  if ((*lit)->mnRelocWords > maxCommonWords)
302  maxCommonWords = (*lit)->mnRelocWords;
303  }
304 
305  int minCommonWords = (int)(maxCommonWords * minCommonWordFactor);
306 
307  if (!applyMinAccScoreFilter)
308  {
309  std::vector<WAIKeyFrame*> vpRelocCandidates;
310 
311  // Compute similarity score.
312  for (std::list<WAIKeyFrame*>::iterator lit = lKFsSharingWords.begin(), lend = lKFsSharingWords.end(); lit != lend; lit++)
313  {
314  WAIKeyFrame* pKFi = *lit;
315 
316  if (pKFi->mnRelocWords > minCommonWords)
317  {
318  vpRelocCandidates.push_back(pKFi);
319  }
320  }
321 
322  return vpRelocCandidates;
323  }
324  else
325  {
326  //apply minimum accumulated score filter:
327  /*We group those keyframes that are connected in the covisibility graph and caluculate an accumulated score.
328  We return all keyframe matches whose scores are higher than the 75 % of the best score.*/
329  std::list<std::pair<float, WAIKeyFrame*>> lScoreAndMatch;
330 
331  // Compute similarity score.
332  for (std::list<WAIKeyFrame*>::iterator lit = lKFsSharingWords.begin(), lend = lKFsSharingWords.end(); lit != lend; lit++)
333  {
334  WAIKeyFrame* pKFi = *lit;
335 
336  if (pKFi->mnRelocWords > minCommonWords)
337  {
338  float si = (float)mpVoc->score(F->mBowVec, pKFi->mBowVec);
339  //std::cout << "si: " << si << std::endl;
340  pKFi->mRelocScore = si;
341  lScoreAndMatch.push_back(std::make_pair(si, pKFi));
342  }
343  }
344 
345  if (lScoreAndMatch.empty())
346  return std::vector<WAIKeyFrame*>();
347 
348  std::list<std::pair<float, WAIKeyFrame*>> lAccScoreAndMatch;
349  float bestAccScore = 0;
350 
351  // Let's now accumulate score by co-visibility
352  for (std::list<std::pair<float, WAIKeyFrame*>>::iterator it = lScoreAndMatch.begin(), itend = lScoreAndMatch.end(); it != itend; it++)
353  {
354  WAIKeyFrame* pKFi = it->second;
355  std::vector<WAIKeyFrame*> vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10);
356 
357  float bestScore = it->first;
358  float accScore = bestScore;
359  WAIKeyFrame* pBestKF = pKFi;
360  for (std::vector<WAIKeyFrame*>::iterator vit = vpNeighs.begin(), vend = vpNeighs.end(); vit != vend; vit++)
361  {
362  WAIKeyFrame* pKF2 = *vit;
363 
364  //TODO (luc)
365  //Evaluate which is the best between avoid bad neighbour or compute the reloc score for all neighbours.
366  if (pKF2->mnRelocQuery != F->mnId && pKF2->mnRelocWords <= minCommonWords)
367  continue;
368 
369  accScore += pKF2->mRelocScore;
370  if (pKF2->mRelocScore > bestScore)
371  {
372  pBestKF = pKF2;
373  bestScore = pKF2->mRelocScore;
374  }
375  }
376  lAccScoreAndMatch.push_back(std::make_pair(accScore, pBestKF));
377  if (accScore > bestAccScore)
378  bestAccScore = accScore;
379  }
380 
381  //std::cout << "lAccScoreAndMatch: " << lAccScoreAndMatch.size() << std::endl;
382 
383  // Return all those keyframes with a score higher than 0.75*bestScore
384  // This ensures that all the neighbours are also
385  float minScoreToRetain = 0.75f * bestAccScore;
386  //std::cout << "minScoreToRetain: " << minScoreToRetain << std::endl;
387  std::set<WAIKeyFrame*> spAlreadyAddedKF;
388  std::vector<WAIKeyFrame*> vpRelocCandidates;
389  vpRelocCandidates.reserve(lAccScoreAndMatch.size());
390  for (std::list<std::pair<float, WAIKeyFrame*>>::iterator it = lAccScoreAndMatch.begin(), itend = lAccScoreAndMatch.end(); it != itend; it++)
391  {
392  const float& si = it->first;
393  //std::cout << "final si: " << si << std::endl;
394 
395  if (si > minScoreToRetain)
396  {
397  WAIKeyFrame* pKFi = it->second;
398  if (!spAlreadyAddedKF.count(pKFi))
399  {
400  vpRelocCandidates.push_back(pKFi);
401  spAlreadyAddedKF.insert(pKFi);
402  }
403  }
404  }
405 
406  return vpRelocCandidates;
407  }
408  /*
409 
410  if (lScoreAndMatch.empty())
411  return vector<WAIKeyFrame*>();
412 
413  list<pair<float, WAIKeyFrame*>> lAccScoreAndMatch;
414  float bestAccScore = 0;
415 
416  // Lets now accumulate score by covisibility
417  for (list<pair<float, WAIKeyFrame*>>::iterator it = lScoreAndMatch.begin(), itend = lScoreAndMatch.end(); it != itend; it++)
418  {
419  WAIKeyFrame* pKFi = it->second;
420  vector<WAIKeyFrame*> vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10);
421 
422  float bestScore = it->first;
423  float accScore = bestScore;
424  WAIKeyFrame* pBestKF = pKFi;
425  std::cout << "vpNeighs: " << vpNeighs.size() << std::endl;
426  for (vector<WAIKeyFrame*>::iterator vit = vpNeighs.begin(), vend = vpNeighs.end(); vit != vend; vit++)
427  {
428  WAIKeyFrame* pKF2 = *vit;
429 
430  //TODO (luc)
431  //Evaluate which is the best between avoid bad neighbour or compute the reloc score for all neighbours.
432  if (pKF2->mnRelocQuery != F->mnId && pKF2->mnRelocWords <= minCommonWords)
433  continue;
434 
435  accScore += pKF2->mRelocScore;
436  if (pKF2->mRelocScore > bestScore)
437  {
438  pBestKF = pKF2;
439  bestScore = pKF2->mRelocScore;
440  }
441  }
442  lAccScoreAndMatch.push_back(make_pair(accScore, pBestKF));
443  if (accScore > bestAccScore)
444  bestAccScore = accScore;
445  }
446 
447  std::cout << "lAccScoreAndMatch: " << lAccScoreAndMatch.size() << std::endl;
448 
449  // Return all those keyframes with a score higher than 0.75*bestScore
450  // This ensures that all the neighbours are also
451  float minScoreToRetain = 0.75f * bestAccScore;
452  std::cout << "minScoreToRetain: " << minScoreToRetain << std::endl;
453  set<WAIKeyFrame*> spAlreadyAddedKF;
454  vector<WAIKeyFrame*> vpRelocCandidates;
455  vpRelocCandidates.reserve(lAccScoreAndMatch.size());
456  for (list<pair<float, WAIKeyFrame*>>::iterator it = lAccScoreAndMatch.begin(), itend = lAccScoreAndMatch.end(); it != itend; it++)
457  {
458  const float& si = it->first;
459  std::cout << "final si: " << si << std::endl;
460 
461  if (si > minScoreToRetain)
462  {
463  WAIKeyFrame* pKFi = it->second;
464  if (!spAlreadyAddedKF.count(pKFi))
465  {
466  vpRelocCandidates.push_back(pKFi);
467  spAlreadyAddedKF.insert(pKFi);
468  }
469  }
470  }
471 
472  return vpRelocCandidates;
473  */
474 }

◆ erase()

void WAIKeyFrameDB::erase ( WAIKeyFrame pKF)

Definition at line 54 of file WAIKeyFrameDB.cpp.

55 {
56  std::unique_lock<std::mutex> lock(mMutex);
57 
58  // Erase elements in the Inverse File for the entry
59  for (auto vit = pKF->mBowVec.getWordScoreMapping().begin(), vend = pKF->mBowVec.getWordScoreMapping().end(); vit != vend; vit++)
60  {
61  // List of keyframes that share the word
62  std::list<WAIKeyFrame*>& lKFs = mvInvertedFile[vit->first];
63 
64  for (std::list<WAIKeyFrame*>::iterator lit = lKFs.begin(), lend = lKFs.end(); lit != lend; lit++)
65  {
66  if (pKF == *lit)
67  {
68  lKFs.erase(lit);
69  break;
70  }
71  }
72  }
73 }

◆ getInvertedFile()

std::vector<std::list<WAIKeyFrame*> >& WAIKeyFrameDB::getInvertedFile ( )
inline

Definition at line 55 of file WAIKeyFrameDB.h.

55 { return mvInvertedFile; }

Member Data Documentation

◆ mMutex

std::mutex WAIKeyFrameDB::mMutex
protected

Definition at line 77 of file WAIKeyFrameDB.h.

◆ mpVoc

WAIOrbVocabulary* WAIKeyFrameDB::mpVoc
protected

Definition at line 72 of file WAIKeyFrameDB.h.

◆ mvInvertedFile

std::vector<std::list<WAIKeyFrame*> > WAIKeyFrameDB::mvInvertedFile
protected

Definition at line 74 of file WAIKeyFrameDB.h.


The documentation for this class was generated from the following files: