Skip to content

Commit c8cd905

Browse files
fix some warnings
1 parent 71c627f commit c8cd905

6 files changed

Lines changed: 86 additions & 105 deletions

File tree

include/Settings.h

Lines changed: 52 additions & 52 deletions
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ class Settings {
6565
/*
6666
* Getter methods
6767
*/
68-
CameraType cameraType() { return cameraType_; }
68+
CameraType cameraType() const { return cameraType_; }
6969
GeometricCamera* camera1() { return calibration1_; }
7070
GeometricCamera* camera2() { return calibration2_; }
7171
cv::Mat camera1DistortionCoef() {
@@ -74,59 +74,59 @@ class Settings {
7474
}
7575
cv::Mat camera2DistortionCoef() {
7676
return cv::Mat(vPinHoleDistorsion2_.size(), 1, CV_32F,
77-
vPinHoleDistorsion1_.data());
77+
vPinHoleDistorsion2_.data());
7878
}
7979

80-
Sophus::SE3f Tlr() { return Tlr_; }
81-
float bf() { return bf_; }
82-
float b() { return b_; }
83-
float thDepth() { return thDepth_; }
84-
85-
bool needToUndistort() { return bNeedToUndistort_; }
86-
87-
cv::Size newImSize() { return newImSize_; }
88-
float fps() { return fps_; }
89-
bool rgb() { return bRGB_; }
90-
bool needToResize() { return bNeedToResize1_; }
91-
bool needToRectify() { return bNeedToRectify_; }
92-
93-
float noiseGyro() { return noiseGyro_; }
94-
float noiseAcc() { return noiseAcc_; }
95-
float gyroWalk() { return gyroWalk_; }
96-
float accWalk() { return accWalk_; }
97-
float imuFrequency() { return imuFrequency_; }
98-
Sophus::SE3f Tbc() { return Tbc_; }
99-
bool insertKFsWhenLost() { return insertKFsWhenLost_; }
100-
101-
float depthMapFactor() { return depthMapFactor_; }
102-
103-
int nFeatures() { return nFeatures_; }
104-
int nLevels() { return nLevels_; }
105-
float initThFAST() { return initThFAST_; }
106-
float minThFAST() { return minThFAST_; }
107-
float scaleFactor() { return scaleFactor_; }
108-
109-
float keyFrameSize() { return keyFrameSize_; }
110-
float keyFrameLineWidth() { return keyFrameLineWidth_; }
111-
float graphLineWidth() { return graphLineWidth_; }
112-
float pointSize() { return pointSize_; }
113-
float cameraSize() { return cameraSize_; }
114-
float cameraLineWidth() { return cameraLineWidth_; }
115-
float viewPointX() { return viewPointX_; }
116-
float viewPointY() { return viewPointY_; }
117-
float viewPointZ() { return viewPointZ_; }
118-
float viewPointF() { return viewPointF_; }
119-
float imageViewerScale() { return imageViewerScale_; }
120-
121-
std::string atlasLoadFile() { return sLoadFrom_; }
122-
std::string atlasSaveFile() { return sSaveto_; }
123-
124-
float thFarPoints() { return thFarPoints_; }
125-
126-
cv::Mat M1l() { return M1l_; }
127-
cv::Mat M2l() { return M2l_; }
128-
cv::Mat M1r() { return M1r_; }
129-
cv::Mat M2r() { return M2r_; }
80+
const Sophus::SE3f &Tlr() const { return Tlr_; }
81+
float bf() const { return bf_; }
82+
float b() const { return b_; }
83+
float thDepth() const { return thDepth_; }
84+
85+
bool needToUndistort() const { return bNeedToUndistort_; }
86+
87+
const cv::Size &newImSize() const { return newImSize_; }
88+
float fps() const { return fps_; }
89+
bool rgb() const { return bRGB_; }
90+
bool needToResize() const { return bNeedToResize1_; }
91+
bool needToRectify() const { return bNeedToRectify_; }
92+
93+
float noiseGyro() const { return noiseGyro_; }
94+
float noiseAcc() const { return noiseAcc_; }
95+
float gyroWalk() const { return gyroWalk_; }
96+
float accWalk() const { return accWalk_; }
97+
float imuFrequency() const { return imuFrequency_; }
98+
const Sophus::SE3f &Tbc() const { return Tbc_; }
99+
bool insertKFsWhenLost() const { return insertKFsWhenLost_; }
100+
101+
float depthMapFactor() const { return depthMapFactor_; }
102+
103+
int nFeatures() const { return nFeatures_; }
104+
int nLevels() const { return nLevels_; }
105+
float initThFAST() const { return initThFAST_; }
106+
float minThFAST() const { return minThFAST_; }
107+
float scaleFactor() const { return scaleFactor_; }
108+
109+
float keyFrameSize() const { return keyFrameSize_; }
110+
float keyFrameLineWidth() const { return keyFrameLineWidth_; }
111+
float graphLineWidth() const { return graphLineWidth_; }
112+
float pointSize() const { return pointSize_; }
113+
float cameraSize() const { return cameraSize_; }
114+
float cameraLineWidth() const { return cameraLineWidth_; }
115+
float viewPointX() const { return viewPointX_; }
116+
float viewPointY() const { return viewPointY_; }
117+
float viewPointZ() const { return viewPointZ_; }
118+
float viewPointF() const { return viewPointF_; }
119+
float imageViewerScale() const { return imageViewerScale_; }
120+
121+
const std::string &atlasLoadFile() const { return sLoadFrom_; }
122+
const std::string &atlasSaveFile() const { return sSaveto_; }
123+
124+
float thFarPoints() const { return thFarPoints_; }
125+
126+
const cv::Mat &M1l() const { return M1l_; }
127+
const cv::Mat &M2l() const { return M2l_; }
128+
const cv::Mat &M1r() const { return M1r_; }
129+
const cv::Mat &M2r() const { return M2r_; }
130130

131131
private:
132132
template <typename T>

include/System.h

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -17,8 +17,7 @@
1717
*/
1818

1919

20-
#ifndef SYSTEM_H
21-
#define SYSTEM_H
20+
#pragma once
2221

2322

2423
#include <unistd.h>
@@ -226,9 +225,6 @@ class System
226225
bool mbActivateLocalizationMode;
227226
bool mbDeactivateLocalizationMode;
228227

229-
// Shutdown flag
230-
bool mbShutDown;
231-
232228
// Tracking state
233229
int mTrackingState;
234230
std::vector<MapPoint*> mTrackedMapPoints;
@@ -245,5 +241,3 @@ class System
245241
};
246242

247243
}// namespace ORB_SLAM
248-
249-
#endif // SYSTEM_H

src/Atlas.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -206,7 +206,7 @@ Map* Atlas::GetCurrentMap(System* sys) {
206206
unique_lock<mutex> lock(mMutexAtlas);
207207
if (!mpCurrentMap) CreateNewMap();
208208
while (mpCurrentMap->IsBad()) {
209-
if (sys != nullptr && sys->isShutDown()) return nullptr;
209+
if (sys != nullptr) return nullptr;
210210
}
211211

212212
return mpCurrentMap;

src/LoopClosing.cc

Lines changed: 23 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -35,9 +35,9 @@ namespace ORB_SLAM3
3535

3636
LoopClosing::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();

src/System.cc

Lines changed: 5 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -52,8 +52,7 @@ System::System(const string& strVocFile, const string& strSettingsFile,
5252
mbReset(false),
5353
mbResetActiveMap(false),
5454
mbActivateLocalizationMode(false),
55-
mbDeactivateLocalizationMode(false),
56-
mbShutDown(false) {
55+
mbDeactivateLocalizationMode(false) {
5756
// Output welcome message
5857
cout << endl
5958
<< "ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, "
@@ -389,10 +388,10 @@ Sophus::SE3f System::TrackRGBD(const cv::Mat& im, const cv::Mat& depthmap,
389388
Sophus::SE3f System::TrackMonocular(const cv::Mat& im, const double& timestamp,
390389
const vector<IMU::Point>& vImuMeas,
391390
string filename) {
392-
{
393-
unique_lock<mutex> lock(mMutexReset);
394-
if (mbShutDown) return Sophus::SE3f();
395-
}
391+
// {
392+
// unique_lock<mutex> lock(mMutexReset);
393+
// if (mbShutDown) return Sophus::SE3f();
394+
// }
396395

397396
if (mSensor != CameraType::MONOCULAR && mSensor != CameraType::IMU_MONOCULAR) {
398397
cerr << "ERROR: you called TrackMonocular but input sensor was not set to "
@@ -525,13 +524,6 @@ System::~System() {
525524
#ifdef REGISTER_TIMES
526525
mpTracker->PrintTimeStats();
527526
#endif
528-
529-
mbShutDown = true;
530-
}
531-
532-
bool System::isShutDown() {
533-
unique_lock<mutex> lock(mMutexReset);
534-
return mbShutDown;
535527
}
536528

537529
void System::SaveTrajectoryTUM(const string& filename) {

src/Tracking.cc

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -39,8 +39,7 @@ using namespace std;
3939

4040
namespace ORB_SLAM3 {
4141

42-
Tracking::Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer,
43-
MapDrawer* pMapDrawer, Atlas* pAtlas,
42+
Tracking::Tracking(System* pSys, ORBVocabulary* pVoc, Atlas* pAtlas,
4443
KeyFrameDatabase* pKFDB, const string& strSettingPath,
4544
const int sensor, Settings* settings, const string& _nameSeq)
4645
: mState(Tracker::NO_IMAGES_YET),
@@ -1705,9 +1704,9 @@ void Tracking::Track() {
17051704

17061705
Map* pCurrentMap = mpAtlas->GetCurrentMap(mpSystem);
17071706
if (!pCurrentMap) {
1708-
if (!mpSystem->isShutDown()){
1709-
cout << "ERROR: There is not an active map in the atlas" << endl;
1710-
}
1707+
// if (!mpSystem->isShutDown()){
1708+
// cout << "ERROR: There is not an active map in the atlas" << endl;
1709+
// }
17111710
return;
17121711
}
17131712

0 commit comments

Comments
 (0)