25 #include<opencv2/core/core.hpp> 26 #include<opencv2/features2d/features2d.hpp> 69 cv::Mat
GrabImageStereo(
const cv::Mat &imRectLeft,
const cv::Mat &imRectRight,
const double ×tamp);
70 cv::Mat
GrabImageRGBD(
const cv::Mat &imRGB,
const cv::Mat &imD,
const double ×tamp);
std::vector< MapPoint * > mvpLocalMapPoints
std::vector< KeyFrame * > mvpLocalKeyFrames
unsigned int mnLastKeyFrameId
unsigned int mnLastRelocFrameId
void SetLoopClosing(LoopClosing *pLoopClosing)
KeyFrame * mpLastKeyFrame
bool TrackWithMotionModel()
std::vector< int > mvIniMatches
Tracking(System *pSys, ORBVocabulary *pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Map *pMap, shared_ptr< PointCloudMapping > pPointCloud, KeyFrameDatabase *pKFDB, const string &strSettingPath, const int sensor)
void SetLocalMapper(LocalMapping *pLocalMapper)
cv::Mat GrabImageRGBD(const cv::Mat &imRGB, const cv::Mat &imD, const double ×tamp)
Initializer * mpInitializer
FrameDrawer * mpFrameDrawer
ORBVocabulary * mpORBVocabulary
KeyFrameDatabase * mpKeyFrameDB
cv::Mat GrabImageStereo(const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double ×tamp)
void SetViewer(Viewer *pViewer)
void MonocularInitialization()
void CreateInitialMapMonocular()
void ChangeCalibration(const string &strSettingPath)
LoopClosing * mpLoopClosing
list< double > mlFrameTimes
ORBextractor * mpORBextractorLeft
void InformOnlyTracking(const bool &flag)
ORBextractor * mpIniORBextractor
list< KeyFrame * > mlpReferences
void CheckReplacedInLastFrame()
void StereoInitialization()
eTrackingState mLastProcessedState
std::vector< int > mvIniLastMatches
shared_ptr< PointCloudMapping > mpPointCloudMapping
bool TrackReferenceKeyFrame()
list< MapPoint * > mlpTemporalPoints
list< cv::Mat > mlRelativeFramePoses
cv::Mat GrabImageMonocular(const cv::Mat &im, const double ×tamp)
void UpdateLocalKeyFrames()
LocalMapping * mpLocalMapper
std::vector< cv::Point3f > mvIniP3D
std::vector< cv::Point2f > mvbPrevMatched
ORBextractor * mpORBextractorRight