1 #ifndef WAI_SLAM_TRACKPOOL_H 
    2 #define WAI_SLAM_TRACKPOOL_H 
   39                      const cv::Mat&          distortion,
 
   41                      KPextractor*            iniExtractor,
 
   42                      KPextractor*            relocExtractor,
 
   43                      KPextractor*            extractor,
 
   44                      std::unique_ptr<WAIMap> globalMap,
 
   49     bool update(cv::Mat& imageGray);
 
   59                   bool     showKeyPointsMatched);
 
   65         return std::vector<WAIMapPoint*>();
 
unsigned int _relocFrameCounter
 
void changeIntrinsic(cv::Mat intrinsic, cv::Mat distortion)
 
KPextractor * _relocExtractor
 
void createFrame(WAIFrame &frame, cv::Mat &imageGray)
 
void drawInfo(cv::Mat &imageBGR, float scale, bool showInitLine, bool showKeyPoints, bool showKeyPointsMatched)
 
virtual WAITrackingState getTrackingState()
 
unsigned long _lastKeyFrameFrameId
 
virtual ~WAISlamTrackPool()
 
bool update(cv::Mat &imageGray)
 
WAISlamTrackPool(const cv::Mat &intrinsic, const cv::Mat &distortion, WAIOrbVocabulary *voc, KPextractor *iniExtractor, KPextractor *relocExtractor, KPextractor *extractor, std::unique_ptr< WAIMap > globalMap, Params params)
 
std::vector< WAIMapPoint * > getMatchedMapPoints()
 
std::mutex _cameraExtrinsicMutex
 
virtual std::vector< WAIMapPoint * > getMapPoints()
 
KPextractor * _iniExtractor
 
void updatePose(WAIFrame &frame)
 
unsigned long _lastRelocFrameId
 
float minCommonWordFactor