Skip to content

fishmarch/ORB_SLAM3_Fixed

 
 

Repository files navigation

Some bugs in ORB-SLAM3

Changed Codes

SearchForTriangulation

vbMatched2[bestIdx2]=true;

Forgot to change flags to label matched features.

This would cause multiple keypoints in KF1 are matched with same keypoint in KF2; and then all these new map points contain obervations KF1, but KF1 only records one of them.

UpdateConnections

for(map<KeyFrame*,int>::iterator mit=KFcounter.begin(), mend=KFcounter.end(); mit!=mend;)
{
if(!upParent)
cout << " UPDATE_CONN: KF " << mit->first->mnId << " ; num matches: " << mit->second << endl;
if(mit->second>nmax)
{
nmax=mit->second;
pKFmax=mit->first;
}
if(mit->second>=th)
{
vPairs.push_back(make_pair(mit->second,mit->first));
(mit->first)->AddConnection(this,mit->second);
mit++;
}else
mit = KFcounter.erase(mit);
}

Here caused unidirectional connection.

When updating connection of KF, all other keyframes sharing co-observed mappoints are collected. Only when the weights (number of co-obervations) are larger than a threshold (15), the connections are recorded bidirectionally; otherwise, the records should be erased.

Sim3Solver

bool bDifferentKFs = true;
if(vpKeyFrameMatchedMP.empty())
{
bDifferentKFs = false;

The flag was set wrong here.

This would cause the index cannot be found properly later, and then less matched map points are collected.

DetectNBestCandidates

KeyFrame* pKFi = it->second;
if(!pKFi->isBad()){
if(!spAlreadyAddedKF.count(pKFi))
{
if(pKF->GetMap() == pKFi->GetMap() && vpLoopCand.size() < nNumCandidates)
{
vpLoopCand.push_back(pKFi);
}
else if(pKF->GetMap() != pKFi->GetMap() && vpMergeCand.size() < nNumCandidates && !pKFi->GetMap()->IsBad())
{
vpMergeCand.push_back(pKFi);
}
spAlreadyAddedKF.insert(pKFi);
}
}
i++;
it++;

The iterator was not updated when the keyframe is bad.

float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec);
pKFi->mPlaceRecognitionScore=si;
if(pKFi->mnPlaceRecognitionWords>minCommonWords)
{
nscores++;
lScoreAndMatch.push_back(make_pair(si,pKFi));
}

Only computed scores for keyframes in which the number of common words is larger than a threshold, but the scores of other keyframes may also be used later.

Update: But this would make this part very slow. Thus the codes are changed as following.

if(pKF2->mnPlaceRecognitionWords<=minCommonWords){
float si = mpVoc->score(pKF->mBowVec,pKF2->mBowVec);
pKF2->mPlaceRecognitionScore=si;
pKF2->mnPlaceRecognitionWords = minCommonWords+1;
}

About

Fixed some bugs of original ORB_SLAM3

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • C++ 98.0%
  • Other 2.0%