#include <Tracking.h>
|
void | ChangeCalibration (const string &strSettingPath) |
|
cv::Mat | GrabImageMonocular (const cv::Mat &im, const double ×tamp) |
|
cv::Mat | GrabImageRGBD (const cv::Mat &imRGB, const cv::Mat &imD, const double ×tamp) |
|
cv::Mat | GrabImageStereo (const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double ×tamp) |
|
void | InformOnlyTracking (const bool &flag) |
|
void | Reset () |
|
void | SetLocalMapper (LocalMapping *pLocalMapper) |
|
void | SetLoopClosing (LoopClosing *pLoopClosing) |
|
void | SetViewer (Viewer *pViewer) |
|
| Tracking (System *pSys, ORBVocabulary *pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Map *pMap, shared_ptr< PointCloudMapping > pPointCloud, KeyFrameDatabase *pKFDB, const string &strSettingPath, const int sensor) |
|
Definition at line 59 of file Tracking.h.
Enumerator |
---|
SYSTEM_NOT_READY |
|
NO_IMAGES_YET |
|
NOT_INITIALIZED |
|
OK |
|
LOST |
|
Definition at line 90 of file Tracking.h.
void ORB_SLAM2::Tracking::ChangeCalibration |
( |
const string & |
strSettingPath | ) |
|
void ORB_SLAM2::Tracking::CheckReplacedInLastFrame |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::CreateInitialMapMonocular |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::CreateNewKeyFrame |
( |
| ) |
|
|
protected |
cv::Mat ORB_SLAM2::Tracking::GrabImageMonocular |
( |
const cv::Mat & |
im, |
|
|
const double & |
timestamp |
|
) |
| |
cv::Mat ORB_SLAM2::Tracking::GrabImageRGBD |
( |
const cv::Mat & |
imRGB, |
|
|
const cv::Mat & |
imD, |
|
|
const double & |
timestamp |
|
) |
| |
cv::Mat ORB_SLAM2::Tracking::GrabImageStereo |
( |
const cv::Mat & |
imRectLeft, |
|
|
const cv::Mat & |
imRectRight, |
|
|
const double & |
timestamp |
|
) |
| |
void ORB_SLAM2::Tracking::InformOnlyTracking |
( |
const bool & |
flag | ) |
|
void ORB_SLAM2::Tracking::MonocularInitialization |
( |
| ) |
|
|
protected |
bool ORB_SLAM2::Tracking::NeedNewKeyFrame |
( |
| ) |
|
|
protected |
bool ORB_SLAM2::Tracking::Relocalization |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::Reset |
( |
| ) |
|
void ORB_SLAM2::Tracking::SearchLocalPoints |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::SetLocalMapper |
( |
LocalMapping * |
pLocalMapper | ) |
|
void ORB_SLAM2::Tracking::SetLoopClosing |
( |
LoopClosing * |
pLoopClosing | ) |
|
void ORB_SLAM2::Tracking::SetViewer |
( |
Viewer * |
pViewer | ) |
|
void ORB_SLAM2::Tracking::StereoInitialization |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::Track |
( |
| ) |
|
|
protected |
bool ORB_SLAM2::Tracking::TrackLocalMap |
( |
| ) |
|
|
protected |
bool ORB_SLAM2::Tracking::TrackReferenceKeyFrame |
( |
| ) |
|
|
protected |
bool ORB_SLAM2::Tracking::TrackWithMotionModel |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::UpdateLastFrame |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::UpdateLocalKeyFrames |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::UpdateLocalMap |
( |
| ) |
|
|
protected |
void ORB_SLAM2::Tracking::UpdateLocalPoints |
( |
| ) |
|
|
protected |
bool ORB_SLAM2::Tracking::loop_detected |
float ORB_SLAM2::Tracking::mbf |
|
protected |
bool ORB_SLAM2::Tracking::mbOnlyTracking |
bool ORB_SLAM2::Tracking::mbRGB |
|
protected |
bool ORB_SLAM2::Tracking::mbVO |
|
protected |
Frame ORB_SLAM2::Tracking::mCurrentFrame |
float ORB_SLAM2::Tracking::mDepthMapFactor |
|
protected |
cv::Mat ORB_SLAM2::Tracking::mDistCoef |
|
protected |
cv::Mat ORB_SLAM2::Tracking::mImDepth |
cv::Mat ORB_SLAM2::Tracking::mImGray |
cv::Mat ORB_SLAM2::Tracking::mImRGB_ZT |
Frame ORB_SLAM2::Tracking::mInitialFrame |
cv::Mat ORB_SLAM2::Tracking::mK |
|
protected |
Frame ORB_SLAM2::Tracking::mLastFrame |
|
protected |
list<bool> ORB_SLAM2::Tracking::mlbLost |
list<double> ORB_SLAM2::Tracking::mlFrameTimes |
list<KeyFrame*> ORB_SLAM2::Tracking::mlpReferences |
list<MapPoint*> ORB_SLAM2::Tracking::mlpTemporalPoints |
|
protected |
list<cv::Mat> ORB_SLAM2::Tracking::mlRelativeFramePoses |
int ORB_SLAM2::Tracking::mMaxFrames |
|
protected |
int ORB_SLAM2::Tracking::mMinFrames |
|
protected |
unsigned int ORB_SLAM2::Tracking::mnLastKeyFrameId |
|
protected |
unsigned int ORB_SLAM2::Tracking::mnLastRelocFrameId |
|
protected |
int ORB_SLAM2::Tracking::mnMatchesInliers |
|
protected |
KeyFrame* ORB_SLAM2::Tracking::mpLastKeyFrame |
|
protected |
Map* ORB_SLAM2::Tracking::mpMap |
|
protected |
KeyFrame* ORB_SLAM2::Tracking::mpReferenceKF |
|
protected |
System* ORB_SLAM2::Tracking::mpSystem |
|
protected |
Viewer* ORB_SLAM2::Tracking::mpViewer |
|
protected |
int ORB_SLAM2::Tracking::mSensor |
float ORB_SLAM2::Tracking::mThDepth |
|
protected |
std::vector<cv::Point2f> ORB_SLAM2::Tracking::mvbPrevMatched |
cv::Mat ORB_SLAM2::Tracking::mVelocity |
|
protected |
std::vector<int> ORB_SLAM2::Tracking::mvIniLastMatches |
std::vector<int> ORB_SLAM2::Tracking::mvIniMatches |
std::vector<cv::Point3f> ORB_SLAM2::Tracking::mvIniP3D |
std::vector<KeyFrame*> ORB_SLAM2::Tracking::mvpLocalKeyFrames |
|
protected |
std::vector<MapPoint*> ORB_SLAM2::Tracking::mvpLocalMapPoints |
|
protected |
The documentation for this class was generated from the following file: