28 #include <opencv2/core/core.hpp> 29 #include <sys/resource.h> 69 void TrackStereo(
const cv::Mat &imLeft,
const cv::Mat &imRight,
const double ×tamp);
75 void TrackRGBD(
const cv::Mat &im,
const cv::Mat &depthmap,
const double ×tamp);
124 bool SaveMap(
const string &filename);
149 bool LoadMap(
const string &filename);
KeyFrameDatabase * mpKeyFrameDatabase
ORBVocabulary * mpVocabulary
std::vector< MapPoint * > GetTrackedMapPoints()
cv::Mat current_position_
std::vector< MapPoint * > mTrackedMapPoints
bool SaveMap(const string &filename)
rlim_t GetCurrentCallStackSize()
void TrackMonocular(const cv::Mat &im, const double ×tamp)
bool currently_localizing_only_
std::thread * mptLocalMapping
LoopClosing * mpLoopCloser
bool SetCallStackSize(const rlim_t kNewStackSize)
System(const string strVocFile, const eSensor sensor, ORBParameters ¶meters, const std::string &map_file="", bool load_map=false)
LocalMapping * mpLocalMapper
void TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double ×tamp)
void EnableLocalizationOnly(bool localize_only)
std::vector< cv::KeyPoint > GetTrackedKeyPointsUn()
std::thread * mptLoopClosing
std::vector< cv::KeyPoint > mTrackedKeyPointsUn
bool mbActivateLocalizationMode
void TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double ×tamp)
void SaveTrajectoryKITTI(const string &filename)
void SaveTrajectoryTUM(const string &filename)
cv::Mat GetCurrentPosition()
bool mbDeactivateLocalizationMode
void DeactivateLocalizationMode()
FrameDrawer * mpFrameDrawer
std::vector< MapPoint * > GetAllMapPoints()
void SaveKeyFrameTrajectoryTUM(const string &filename)
bool LoadMap(const string &filename)
void ActivateLocalizationMode()
cv::Mat DrawCurrentFrame()
void SetMinimumKeyFrames(int min_num_kf)