orb_slam3_details/include/Tracking.h

376 lines
9.9 KiB
C
Raw Normal View History

2020-12-01 11:58:17 +08:00
/**
* This file is part of ORB-SLAM3
*
2022-03-28 21:20:28 +08:00
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
2020-12-01 11:58:17 +08:00
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 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-SLAM3 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-SLAM3.
* If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef TRACKING_H
#define TRACKING_H
2022-03-28 21:20:28 +08:00
#include <opencv2/core/core.hpp>
#include <opencv2/features2d/features2d.hpp>
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
#include "Viewer.h"
#include "FrameDrawer.h"
#include "Atlas.h"
#include "LocalMapping.h"
#include "LoopClosing.h"
#include "Frame.h"
2020-12-01 11:58:17 +08:00
#include "ORBVocabulary.h"
2022-03-28 21:20:28 +08:00
#include "KeyFrameDatabase.h"
#include "ORBextractor.h"
2020-12-01 11:58:17 +08:00
#include "MapDrawer.h"
#include "System.h"
#include "ImuTypes.h"
2022-03-28 21:20:28 +08:00
#include "Settings.h"
2020-12-01 11:58:17 +08:00
#include "GeometricCamera.h"
#include <mutex>
#include <unordered_set>
namespace ORB_SLAM3
{
class Viewer;
class FrameDrawer;
class Atlas;
class LocalMapping;
class LoopClosing;
class System;
2022-03-28 21:20:28 +08:00
class Settings;
2020-12-01 11:58:17 +08:00
class Tracking
{
public:
2022-03-28 21:20:28 +08:00
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
2020-12-01 11:58:17 +08:00
Tracking(System* pSys, ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Atlas* pAtlas,
2022-03-28 21:20:28 +08:00
KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor, Settings* settings, const string &_nameSeq=std::string());
2020-12-01 11:58:17 +08:00
~Tracking();
// Parse the config file
bool ParseCamParamFile(cv::FileStorage &fSettings);
bool ParseORBParamFile(cv::FileStorage &fSettings);
bool ParseIMUParamFile(cv::FileStorage &fSettings);
// Preprocess the input and call Track(). Extract features and performs stereo matching.
2022-03-28 21:20:28 +08:00
Sophus::SE3f GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double &timestamp, string filename);
Sophus::SE3f GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double &timestamp, string filename);
Sophus::SE3f GrabImageMonocular(const cv::Mat &im, const double &timestamp, string filename);
2020-12-01 11:58:17 +08:00
void GrabImuData(const IMU::Point &imuMeasurement);
2022-03-28 21:20:28 +08:00
2020-12-01 11:58:17 +08:00
void SetLocalMapper(LocalMapping* pLocalMapper);
void SetLoopClosing(LoopClosing* pLoopClosing);
void SetViewer(Viewer* pViewer);
void SetStepByStep(bool bSet);
2022-03-28 21:20:28 +08:00
bool GetStepByStep();
2020-12-01 11:58:17 +08:00
// Load new settings
// The focal lenght should be similar or scale prediction will fail when projecting points
void ChangeCalibration(const string &strSettingPath);
// Use this function if you have deactivated local mapping and you only want to localize the camera.
void InformOnlyTracking(const bool &flag);
2022-03-28 21:20:28 +08:00
2020-12-01 11:58:17 +08:00
void UpdateFrameIMU(const float s, const IMU::Bias &b, KeyFrame* pCurrentKeyFrame);
KeyFrame* GetLastKeyFrame()
{
return mpLastKeyFrame;
}
2022-03-28 21:20:28 +08:00
2020-12-01 11:58:17 +08:00
void CreateMapInAtlas();
2022-03-28 21:20:28 +08:00
//std::mutex mMutexTracks;
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
//--
2020-12-01 11:58:17 +08:00
void NewDataset();
int GetNumberDataset();
int GetMatchesInliers();
2022-03-28 21:20:28 +08:00
//DEBUG
void SaveSubTrajectory(string strNameFile_frames, string strNameFile_kf, string strFolder="");
void SaveSubTrajectory(string strNameFile_frames, string strNameFile_kf, Map* pMap);
float GetImageScale();
#ifdef REGISTER_LOOP
void RequestStop();
bool isStopped();
void Release();
bool stopRequested();
#endif
2020-12-01 11:58:17 +08:00
public:
// Tracking states
enum eTrackingState{
2022-03-28 21:20:28 +08:00
SYSTEM_NOT_READY=-1,
NO_IMAGES_YET=0,
NOT_INITIALIZED=1,
OK=2,
RECENTLY_LOST=3,
LOST=4,
OK_KLT=5
2020-12-01 11:58:17 +08:00
};
eTrackingState mState;
eTrackingState mLastProcessedState;
// Input sensor
int mSensor;
// Current Frame
Frame mCurrentFrame;
2022-03-28 21:20:28 +08:00
Frame mLastFrame;
2020-12-01 11:58:17 +08:00
cv::Mat mImGray;
// Initialization Variables (Monocular)
std::vector<int> mvIniLastMatches;
std::vector<int> mvIniMatches;
std::vector<cv::Point2f> mvbPrevMatched;
std::vector<cv::Point3f> mvIniP3D;
Frame mInitialFrame;
// Lists used to recover the full camera trajectory at the end of the execution.
// Basically we store the reference keyframe for each frame and its relative transformation
2022-03-28 21:20:28 +08:00
list<Sophus::SE3f> mlRelativeFramePoses;
2020-12-01 11:58:17 +08:00
list<KeyFrame*> mlpReferences;
list<double> mlFrameTimes;
list<bool> mlbLost;
// frames with estimated pose
int mTrackedFr;
bool mbStep;
// True if local mapping is deactivated and we are performing only localization
bool mbOnlyTracking;
void Reset(bool bLocMap = false);
void ResetActiveMap(bool bLocMap = false);
float mMeanTrack;
bool mbInitWith3KFs;
double t0; // time-stamp of first read frame
double t0vis; // time-stamp of first inserted keyframe
double t0IMU; // time-stamp of IMU initialization
2022-03-28 21:20:28 +08:00
bool mFastInit = false;
2020-12-01 11:58:17 +08:00
vector<MapPoint*> GetLocalMapMPS();
2021-08-09 19:34:51 +08:00
bool mbWriteStats;
2020-12-01 11:58:17 +08:00
2021-08-09 19:34:51 +08:00
#ifdef REGISTER_TIMES
void LocalMapStats2File();
void TrackStats2File();
void PrintTimeStats();
2020-12-01 11:58:17 +08:00
2021-08-09 19:34:51 +08:00
vector<double> vdRectStereo_ms;
2022-03-28 21:20:28 +08:00
vector<double> vdResizeImage_ms;
2021-08-09 19:34:51 +08:00
vector<double> vdORBExtract_ms;
vector<double> vdStereoMatch_ms;
vector<double> vdIMUInteg_ms;
vector<double> vdPosePred_ms;
vector<double> vdLMTrack_ms;
vector<double> vdNewKF_ms;
vector<double> vdTrackTotal_ms;
#endif
2020-12-01 11:58:17 +08:00
protected:
// Main tracking function. It is independent of the input sensor.
2022-03-28 21:20:28 +08:00
void Track();
2020-12-01 11:58:17 +08:00
// Map initialization for stereo and RGB-D
2022-03-28 21:20:28 +08:00
void StereoInitialization();
2020-12-01 11:58:17 +08:00
// Map initialization for monocular
2022-03-28 21:20:28 +08:00
void MonocularInitialization();
//void CreateNewMapPoints();
void CreateInitialMapMonocular();
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
void CheckReplacedInLastFrame();
bool TrackReferenceKeyFrame();
void UpdateLastFrame();
bool TrackWithMotionModel();
bool PredictStateIMU();
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
bool Relocalization();
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
void UpdateLocalMap();
void UpdateLocalPoints();
void UpdateLocalKeyFrames();
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
bool TrackLocalMap();
void SearchLocalPoints();
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
bool NeedNewKeyFrame();
void CreateNewKeyFrame();
2020-12-01 11:58:17 +08:00
// Perform preintegration from last frame
2022-03-28 21:20:28 +08:00
void PreintegrateIMU();
2020-12-01 11:58:17 +08:00
// Reset IMU biases and compute frame velocity
2022-03-28 21:20:28 +08:00
void ResetFrameIMU();
2020-12-01 11:58:17 +08:00
bool mbMapUpdated;
// Imu preintegration from last frame
IMU::Preintegrated *mpImuPreintegratedFromLastKF;
// Queue of IMU measurements between frames
2022-03-28 21:20:28 +08:00
std::list<IMU::Point> mlQueueImuData;
2020-12-01 11:58:17 +08:00
// Vector of IMU measurements from previous to current frame (to be filled by PreintegrateIMU)
std::vector<IMU::Point> mvImuFromLastFrame;
std::mutex mMutexImuQueue;
// Imu calibration parameters
2022-03-28 21:20:28 +08:00
IMU::Calib *mpImuCalib;
2020-12-01 11:58:17 +08:00
// Last Bias Estimation (at keyframe creation)
IMU::Bias mLastBias;
// In case of performing only localization, this flag is true when there are no matches to
// points in the map. Still tracking will continue if there are enough matches with temporal points.
// In that case we are doing visual odometry. The system will try to do relocalization to recover
// "zero-drift" localization to the map.
bool mbVO;
//Other Thread Pointers
LocalMapping* mpLocalMapper;
LoopClosing* mpLoopClosing;
2022-03-28 21:20:28 +08:00
//ORB
2020-12-01 11:58:17 +08:00
ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
ORBextractor* mpIniORBextractor;
//BoW
ORBVocabulary* mpORBVocabulary;
KeyFrameDatabase* mpKeyFrameDB;
// Initalization (only for monocular)
2022-03-28 21:20:28 +08:00
bool mbReadyToInitializate;
2020-12-01 11:58:17 +08:00
bool mbSetInit;
//Local Map
KeyFrame* mpReferenceKF;
std::vector<KeyFrame*> mvpLocalKeyFrames;
std::vector<MapPoint*> mvpLocalMapPoints;
// System
System* mpSystem;
//Drawers
Viewer* mpViewer;
FrameDrawer* mpFrameDrawer;
MapDrawer* mpMapDrawer;
bool bStepByStep;
//Atlas
Atlas* mpAtlas;
//Calibration matrix
cv::Mat mK;
2022-03-28 21:20:28 +08:00
Eigen::Matrix3f mK_;
2020-12-01 11:58:17 +08:00
cv::Mat mDistCoef;
float mbf;
2022-03-28 21:20:28 +08:00
float mImageScale;
float mImuFreq;
double mImuPer;
bool mInsertKFsLost;
2020-12-01 11:58:17 +08:00
//New KeyFrame rules (according to fps)
int mMinFrames;
int mMaxFrames;
int mnFirstImuFrameId;
int mnFramesToResetIMU;
// Threshold close/far points
// Points seen as close by the stereo/RGBD sensor are considered reliable
// and inserted from just one frame. Far points requiere a match in two keyframes.
2022-03-28 21:20:28 +08:00
float mThDepth;
2020-12-01 11:58:17 +08:00
// For RGB-D inputs only. For some datasets (e.g. TUM) the depthmap values are scaled.
2022-03-28 21:20:28 +08:00
float mDepthMapFactor;
2020-12-01 11:58:17 +08:00
//Current matches in frame
2022-03-28 21:20:28 +08:00
int mnMatchesInliers;
2020-12-01 11:58:17 +08:00
//Last Frame, KeyFrame and Relocalisation Info
KeyFrame* mpLastKeyFrame;
unsigned int mnLastKeyFrameId;
unsigned int mnLastRelocFrameId;
double mTimeStampLost;
double time_recently_lost;
unsigned int mnFirstFrameId;
unsigned int mnInitialFrameId;
unsigned int mnLastInitFrameId;
bool mbCreatedMap;
//Motion Model
2022-03-28 21:20:28 +08:00
bool mbVelocity{false};
Sophus::SE3f mVelocity;
2020-12-01 11:58:17 +08:00
//Color order (true RGB, false BGR, ignored if grayscale)
bool mbRGB;
2022-03-28 21:20:28 +08:00
list<MapPoint*> mlpTemporalPoints;
2020-12-01 11:58:17 +08:00
//int nMapChangeIndex;
int mnNumDataset;
ofstream f_track_stats;
ofstream f_track_times;
double mTime_PreIntIMU;
double mTime_PosePred;
double mTime_LocalMapTrack;
double mTime_NewKF_Dec;
2022-03-28 21:20:28 +08:00
GeometricCamera* mpCamera, *mpCamera2;
2020-12-01 11:58:17 +08:00
int initID, lastID;
2022-03-28 21:20:28 +08:00
Sophus::SE3f mTlr;
void newParameterLoader(Settings* settings);
#ifdef REGISTER_LOOP
bool Stop();
bool mbStopped;
bool mbStopRequested;
bool mbNotStop;
std::mutex mMutexStop;
#endif
2020-12-01 11:58:17 +08:00
public:
cv::Mat mImRight;
};
} //namespace ORB_SLAM
#endif // TRACKING_H