@@ -35,9 +35,9 @@ namespace ORB_SLAM3
3535
3636LoopClosing::LoopClosing (Atlas *pAtlas, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale, const bool bActiveLC):
3737 mbResetRequested (false ), mbResetActiveMapRequested(false ), mbFinishRequested(false ), mbFinished(true ), mpAtlas(pAtlas),
38- mpKeyFrameDB (pDB), mpORBVocabulary(pVoc), mpMatchedKF(NULL ), mbRunningGBA (false ), mbFinishedGBA( true ),
39- mbStopGBA (false ), mpThreadGBA( NULL ), mbFixScale(bFixScale), mnFullBAIdx( 0 ), mnLoopNumCoincidences( 0 ), mnMergeNumCoincidences( 0 ),
40- mbLoopDetected (false ), mbMergeDetected( false ), mnLoopNumNotFound( 0 ), mnMergeNumNotFound (0 ), mbActiveLC(bActiveLC)
38+ mpKeyFrameDB (pDB), mpORBVocabulary(pVoc), mpMatchedKF(NULL ), mbLoopDetected (false ), mnLoopNumCoincidences( 0 ), mnLoopNumNotFound( 0 ),
39+ mbMergeDetected (false ), mnMergeNumCoincidences( 0 ), mnMergeNumNotFound( 0 ), mbRunningGBA( false ), mbFinishedGBA( true ),
40+ mbStopGBA (false ), mpThreadGBA( NULL ), mbFixScale(bFixScale ), mnFullBAIdx (0 ), mbActiveLC(bActiveLC)
4141{
4242 mnCovisibilityConsistencyTh = 3 ;
4343 mpLastCurrentKF = static_cast <KeyFrame*>(NULL );
@@ -134,7 +134,7 @@ void LoopClosing::Run()
134134 Sophus::SE3d mTcw = mpCurrentKF->GetPose ().cast <double >();
135135 g2o::Sim3 gScw1 (mTcw .unit_quaternion (), mTcw .translation (), 1.0 );
136136 g2o::Sim3 gSw2c = mg2oMergeSlw.inverse ();
137- g2o::Sim3 gSw1m = mg2oMergeSlw;
137+ // g2o::Sim3 gSw1m = mg2oMergeSlw; // UNUSED
138138
139139 mSold_new = (gSw2c * gScw1 );
140140
@@ -365,14 +365,14 @@ bool LoopClosing::NewDetectCommonRegions()
365365 // Check the last candidates with geometric validation
366366 // Loop candidates
367367 bool bLoopDetectedInKF = false ;
368- bool bCheckSpatial = false ;
368+ // bool bCheckSpatial = false; // UNUSED
369369
370370#ifdef REGISTER_TIMES
371371 std::chrono::steady_clock::time_point time_StartEstSim3_1 = std::chrono::steady_clock::now ();
372372#endif
373373 if (mnLoopNumCoincidences > 0 )
374374 {
375- bCheckSpatial = true ;
375+ // bCheckSpatial = true; // UNUSED
376376 // Find from the last KF candidates
377377 Sophus::SE3d mTcl = (mpCurrentKF->GetPose () * mpLoopLastCurrentKF->GetPoseInverse ()).cast <double >();
378378 g2o::Sim3 gScl (mTcl .unit_quaternion (),mTcl .translation (),1.0 );
@@ -625,7 +625,7 @@ bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand,
625625
626626
627627 bool bAbortByNearKF = false ;
628- for (int j=0 ; j<vpCovKFi.size (); ++j)
628+ for (size_t j=0 ; j<vpCovKFi.size (); ++j)
629629 {
630630 if (spConnectedKeyFrames.find (vpCovKFi[j]) != spConnectedKeyFrames.end ())
631631 {
@@ -653,7 +653,7 @@ bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand,
653653 std::vector<KeyFrame*> vpKeyFrameMatchedMP = std::vector<KeyFrame*>(mpCurrentKF->GetMapPointMatches ().size (), static_cast <KeyFrame*>(NULL ));
654654
655655 int nIndexMostBoWMatchesKF=0 ;
656- for (int j=0 ; j<vpCovKFi.size (); ++j)
656+ for (size_t j=0 ; j<vpCovKFi.size (); ++j)
657657 {
658658 if (!vpCovKFi[j] || vpCovKFi[j]->isBad ())
659659 continue ;
@@ -666,9 +666,9 @@ bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand,
666666 }
667667 }
668668
669- for (int j=0 ; j<vpCovKFi.size (); ++j)
669+ for (size_t j=0 ; j<vpCovKFi.size (); ++j)
670670 {
671- for (int k=0 ; k < vvpMatchedMPs[j].size (); ++k)
671+ for (size_t k=0 ; k < vvpMatchedMPs[j].size (); ++k)
672672 {
673673 MapPoint* pMPi_j = vvpMatchedMPs[j][k];
674674 if (!pMPi_j || pMPi_j->isBad ())
@@ -759,9 +759,9 @@ bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand,
759759 // Optimize Sim3 transformation with every matches
760760 Eigen::Matrix<double , 7 , 7 > mHessian7x7 ;
761761
762- bool bFixedScale = mbFixScale;
763- if (mpTracker->mSensor ==CameraType::IMU_MONOCULAR && !mpCurrentKF->GetMap ()->GetIniertialBA2 ())
764- bFixedScale=false ;
762+ // bool bFixedScale = mbFixScale; // UNUSED
763+ // if(mpTracker->mSensor==CameraType::IMU_MONOCULAR && !mpCurrentKF->GetMap()->GetIniertialBA2())
764+ // bFixedScale=false; // UNUSED
765765
766766 int numOptMatches = Optimizer::OptimizeSim3 (mpCurrentKF, pKFi, vpMatchedMP, gScm , 10 , mbFixScale, mHessian7x7 , true );
767767
@@ -817,8 +817,7 @@ bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand,
817817 // Check the Sim3 transformation with the current KeyFrame covisibles
818818 vector<KeyFrame*> vpCurrentCovKFs = mpCurrentKF->GetBestCovisibilityKeyFrames (nNumCovisibles);
819819
820- int j = 0 ;
821- while (nNumKFs < 3 && j<vpCurrentCovKFs.size ())
820+ for (size_t j = 0 ; nNumKFs < 3 && j<vpCurrentCovKFs.size (); ++j)
822821 {
823822 KeyFrame* pKFj = vpCurrentCovKFs[j];
824823 Sophus::SE3d mTjc = (pKFj->GetPose () * mpCurrentKF->GetPoseInverse ()).cast <double >();
@@ -830,13 +829,12 @@ bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand,
830829
831830 if (bValid)
832831 {
833- Sophus::SE3f Tc_w = mpCurrentKF->GetPose ();
834- Sophus::SE3f Tw_cj = pKFj->GetPoseInverse ();
835- Sophus::SE3f Tc_cj = Tc_w * Tw_cj;
836- Eigen::Vector3f vector_dist = Tc_cj.translation ();
832+ // Sophus::SE3f Tc_w = mpCurrentKF->GetPose();
833+ // Sophus::SE3f Tw_cj = pKFj->GetPoseInverse();
834+ // Sophus::SE3f Tc_cj = Tc_w * Tw_cj;
835+ // Eigen::Vector3f vector_dist = Tc_cj.translation();
837836 nNumKFs++;
838837 }
839- j++;
840838 }
841839
842840 if (nNumKFs < 3 )
@@ -881,13 +879,13 @@ bool LoopClosing::DetectCommonRegionsFromBoW(std::vector<KeyFrame*> &vpBowCand,
881879 else
882880 {
883881 int maxStage = -1 ;
884- int maxMatched;
885- for (int i=0 ; i<vnStage.size (); ++i)
882+ // int maxMatched; // UNUSED
883+ for (size_t i=0 ; i<vnStage.size (); ++i)
886884 {
887885 if (vnStage[i] > maxStage)
888886 {
889887 maxStage = vnStage[i];
890- maxMatched = vnMatchesStage[i];
888+ // maxMatched = vnMatchesStage[i]; // UNUSED
891889 }
892890 }
893891 }
@@ -925,15 +923,13 @@ int LoopClosing::FindMatchesByProjection(KeyFrame* pCurrentKF, KeyFrame* pMatche
925923 {
926924 vector<KeyFrame*> vpKFs = vpCovKFm[i]->GetBestCovisibilityKeyFrames (nNumCovisibles);
927925 int nInserted = 0 ;
928- int j = 0 ;
929- while (j < vpKFs.size () && nInserted < nNumCovisibles)
926+ for (size_t j = 0 ; j < vpKFs.size () && nInserted < nNumCovisibles; ++j)
930927 {
931928 if (spCheckKFs.find (vpKFs[j]) == spCheckKFs.end () && spCurrentCovisbles.find (vpKFs[j]) == spCurrentCovisbles.end ())
932929 {
933930 spCheckKFs.insert (vpKFs[j]);
934931 ++nInserted;
935932 }
936- ++j;
937933 }
938934 vpCovKFm.insert (vpCovKFm.end (), vpKFs.begin (), vpKFs.end ());
939935 }
@@ -1306,7 +1302,7 @@ void LoopClosing::MergeLocal()
13061302 spLocalWindowKFs.insert (mpCurrentKF);
13071303 const int nMaxTries = 5 ;
13081304 int nNumTries = 0 ;
1309- while (spLocalWindowKFs.size () < numTemporalKFs && nNumTries < nMaxTries)
1305+ while (static_cast < int >( spLocalWindowKFs.size () ) < numTemporalKFs && nNumTries < nMaxTries)
13101306 {
13111307 vector<KeyFrame*> vpNewCovKFs;
13121308 vpNewCovKFs.empty ();
0 commit comments