KeyFrameDatabase.cc
Go to the documentation of this file.
1 
21 #include "KeyFrameDatabase.h"
22 
23 #include "KeyFrame.h"
25 
26 #include<mutex>
27 
28 using namespace std;
29 
30 namespace ORB_SLAM2
31 {
32 
33 KeyFrameDatabase::KeyFrameDatabase (const ORBVocabulary &voc):
34  mpVoc(&voc)
35 {
36  mvInvertedFile.resize(voc.size());
37 }
38 
39 
41 {
42  unique_lock<mutex> lock(mMutex);
43 
44  for(DBoW2::BowVector::const_iterator vit= pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++)
45  mvInvertedFile[vit->first].push_back(pKF);
46 }
47 
49 {
50  unique_lock<mutex> lock(mMutex);
51 
52  // Erase elements in the Inverse File for the entry
53  for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++)
54  {
55  // List of keyframes that share the word
56  list<KeyFrame*> &lKFs = mvInvertedFile[vit->first];
57 
58  for(list<KeyFrame*>::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++)
59  {
60  if(pKF==*lit)
61  {
62  lKFs.erase(lit);
63  break;
64  }
65  }
66  }
67 }
68 
70 {
71  mvInvertedFile.clear();
72  mvInvertedFile.resize(mpVoc->size());
73 }
74 
75 
76 vector<KeyFrame*> KeyFrameDatabase::DetectLoopCandidates(KeyFrame* pKF, float minScore)
77 {
78  set<KeyFrame*> spConnectedKeyFrames = pKF->GetConnectedKeyFrames();
79  list<KeyFrame*> lKFsSharingWords;
80 
81  // Search all keyframes that share a word with current keyframes
82  // Discard keyframes connected to the query keyframe
83  {
84  unique_lock<mutex> lock(mMutex);
85 
86  for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++)
87  {
88  list<KeyFrame*> &lKFs = mvInvertedFile[vit->first];
89 
90  for(list<KeyFrame*>::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++)
91  {
92  KeyFrame* pKFi=*lit;
93  if(pKFi->mnLoopQuery!=pKF->mnId)
94  {
95  pKFi->mnLoopWords=0;
96  if(!spConnectedKeyFrames.count(pKFi))
97  {
98  pKFi->mnLoopQuery=pKF->mnId;
99  lKFsSharingWords.push_back(pKFi);
100  }
101  }
102  pKFi->mnLoopWords++;
103  }
104  }
105  }
106 
107  if(lKFsSharingWords.empty())
108  return vector<KeyFrame*>();
109 
110  list<pair<float,KeyFrame*> > lScoreAndMatch;
111 
112  // Only compare against those keyframes that share enough words
113  int maxCommonWords=0;
114  for(list<KeyFrame*>::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
115  {
116  if((*lit)->mnLoopWords>maxCommonWords)
117  maxCommonWords=(*lit)->mnLoopWords;
118  }
119 
120  int minCommonWords = maxCommonWords*0.8f;
121 
122  int nscores=0;
123 
124  // Compute similarity score. Retain the matches whose score is higher than minScore
125  for(list<KeyFrame*>::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
126  {
127  KeyFrame* pKFi = *lit;
128 
129  if(pKFi->mnLoopWords>minCommonWords)
130  {
131  nscores++;
132 
133  float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec);
134 
135  pKFi->mLoopScore = si;
136  if(si>=minScore)
137  lScoreAndMatch.push_back(make_pair(si,pKFi));
138  }
139  }
140 
141  if(lScoreAndMatch.empty())
142  return vector<KeyFrame*>();
143 
144  list<pair<float,KeyFrame*> > lAccScoreAndMatch;
145  float bestAccScore = minScore;
146 
147  // Lets now accumulate score by covisibility
148  for(list<pair<float,KeyFrame*> >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++)
149  {
150  KeyFrame* pKFi = it->second;
151  vector<KeyFrame*> vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10);
152 
153  float bestScore = it->first;
154  float accScore = it->first;
155  KeyFrame* pBestKF = pKFi;
156  for(vector<KeyFrame*>::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++)
157  {
158  KeyFrame* pKF2 = *vit;
159  if(pKF2->mnLoopQuery==pKF->mnId && pKF2->mnLoopWords>minCommonWords)
160  {
161  accScore+=pKF2->mLoopScore;
162  if(pKF2->mLoopScore>bestScore)
163  {
164  pBestKF=pKF2;
165  bestScore = pKF2->mLoopScore;
166  }
167  }
168  }
169 
170  lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF));
171  if(accScore>bestAccScore)
172  bestAccScore=accScore;
173  }
174 
175  // Return all those keyframes with a score higher than 0.75*bestScore
176  float minScoreToRetain = 0.75f*bestAccScore;
177 
178  set<KeyFrame*> spAlreadyAddedKF;
179  vector<KeyFrame*> vpLoopCandidates;
180  vpLoopCandidates.reserve(lAccScoreAndMatch.size());
181 
182  for(list<pair<float,KeyFrame*> >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++)
183  {
184  if(it->first>minScoreToRetain)
185  {
186  KeyFrame* pKFi = it->second;
187  if(!spAlreadyAddedKF.count(pKFi))
188  {
189  vpLoopCandidates.push_back(pKFi);
190  spAlreadyAddedKF.insert(pKFi);
191  }
192  }
193  }
194 
195 
196  return vpLoopCandidates;
197 }
198 
200 {
201  list<KeyFrame*> lKFsSharingWords;
202 
203  // Search all keyframes that share a word with current frame
204  {
205  unique_lock<mutex> lock(mMutex);
206 
207  for(DBoW2::BowVector::const_iterator vit=F->mBowVec.begin(), vend=F->mBowVec.end(); vit != vend; vit++)
208  {
209  list<KeyFrame*> &lKFs = mvInvertedFile[vit->first];
210 
211  for(list<KeyFrame*>::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++)
212  {
213  KeyFrame* pKFi=*lit;
214  if(pKFi->mnRelocQuery!=F->mnId)
215  {
216  pKFi->mnRelocWords=0;
217  pKFi->mnRelocQuery=F->mnId;
218  lKFsSharingWords.push_back(pKFi);
219  }
220  pKFi->mnRelocWords++;
221  }
222  }
223  }
224  if(lKFsSharingWords.empty())
225  return vector<KeyFrame*>();
226 
227  // Only compare against those keyframes that share enough words
228  int maxCommonWords=0;
229  for(list<KeyFrame*>::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
230  {
231  if((*lit)->mnRelocWords>maxCommonWords)
232  maxCommonWords=(*lit)->mnRelocWords;
233  }
234 
235  int minCommonWords = maxCommonWords*0.8f;
236 
237  list<pair<float,KeyFrame*> > lScoreAndMatch;
238 
239  int nscores=0;
240 
241  // Compute similarity score.
242  for(list<KeyFrame*>::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++)
243  {
244  KeyFrame* pKFi = *lit;
245 
246  if(pKFi->mnRelocWords>minCommonWords)
247  {
248  nscores++;
249  float si = mpVoc->score(F->mBowVec,pKFi->mBowVec);
250  pKFi->mRelocScore=si;
251  lScoreAndMatch.push_back(make_pair(si,pKFi));
252  }
253  }
254 
255  if(lScoreAndMatch.empty())
256  return vector<KeyFrame*>();
257 
258  list<pair<float,KeyFrame*> > lAccScoreAndMatch;
259  float bestAccScore = 0;
260 
261  // Lets now accumulate score by covisibility
262  for(list<pair<float,KeyFrame*> >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++)
263  {
264  KeyFrame* pKFi = it->second;
265  vector<KeyFrame*> vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10);
266 
267  float bestScore = it->first;
268  float accScore = bestScore;
269  KeyFrame* pBestKF = pKFi;
270  for(vector<KeyFrame*>::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++)
271  {
272  KeyFrame* pKF2 = *vit;
273  if(pKF2->mnRelocQuery!=F->mnId)
274  continue;
275 
276  accScore+=pKF2->mRelocScore;
277  if(pKF2->mRelocScore>bestScore)
278  {
279  pBestKF=pKF2;
280  bestScore = pKF2->mRelocScore;
281  }
282 
283  }
284  lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF));
285  if(accScore>bestAccScore)
286  bestAccScore=accScore;
287  }
288 
289  // Return all those keyframes with a score higher than 0.75*bestScore
290  float minScoreToRetain = 0.75f*bestAccScore;
291  set<KeyFrame*> spAlreadyAddedKF;
292  vector<KeyFrame*> vpRelocCandidates;
293  vpRelocCandidates.reserve(lAccScoreAndMatch.size());
294  for(list<pair<float,KeyFrame*> >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++)
295  {
296  const float &si = it->first;
297  if(si>minScoreToRetain)
298  {
299  KeyFrame* pKFi = it->second;
300  if(!spAlreadyAddedKF.count(pKFi))
301  {
302  vpRelocCandidates.push_back(pKFi);
303  spAlreadyAddedKF.insert(pKFi);
304  }
305  }
306  }
307 
308  return vpRelocCandidates;
309 }
310 
311 // map serialization addition
312 template<class Archive>
313 void KeyFrameDatabase::serialize(Archive &ar, const unsigned int version)
314 {
315  // don't save associated vocabulary, KFDB restore by created explicitly from a new ORBvocabulary instance
316  // inverted file
317  {
318  unique_lock<mutex> lock_InvertedFile(mMutex);
319  ar & mvInvertedFile;
320  }
321  // don't save mutex
322 }
323 template void KeyFrameDatabase::serialize(boost::archive::binary_iarchive&, const unsigned int);
324 template void KeyFrameDatabase::serialize(boost::archive::binary_oarchive&, const unsigned int);
325 
326 
327 } //namespace ORB_SLAM
std::vector< KeyFrame * > GetBestCovisibilityKeyFrames(const int &N)
Definition: KeyFrame.cc:174
double score(const BowVector &a, const BowVector &b) const
std::vector< KeyFrame * > DetectRelocalizationCandidates(Frame *F)
std::set< KeyFrame * > GetConnectedKeyFrames()
Definition: KeyFrame.cc:159
std::vector< list< KeyFrame * > > mvInvertedFile
long unsigned int mnLoopQuery
Definition: KeyFrame.h:145
long unsigned int mnRelocQuery
Definition: KeyFrame.h:148
void serialize(Archive &ar, const unsigned int version)
DBoW2::BowVector mBowVec
Definition: KeyFrame.h:171
virtual unsigned int size() const
std::vector< KeyFrame * > DetectLoopCandidates(KeyFrame *pKF, float minScore)
const ORBVocabulary * mpVoc
long unsigned int mnId
Definition: Frame.h:168
DBoW2::BowVector mBowVec
Definition: Frame.h:146
long unsigned int mnId
Definition: KeyFrame.h:125


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