25 #include "Thirdparty/DBoW2/DBoW2/BowVector.h" 26 #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" 27 #include "ORBVocabulary.h" 28 #include "ORBextractor.h" 30 #include "KeyFrameDatabase.h" 41 class KeyFrameDatabase;
49 void SetPose(
const cv::Mat &Tcw);
51 cv::Mat GetPoseInverse();
52 cv::Mat GetCameraCenter();
53 cv::Mat GetStereoCenter();
54 cv::Mat GetRotation();
55 cv::Mat GetTranslation();
61 void AddConnection(
KeyFrame* pKF,
const int &weight);
63 void UpdateConnections();
64 void UpdateBestCovisibles();
65 std::set<KeyFrame *> GetConnectedKeyFrames();
66 std::vector<KeyFrame* > GetVectorCovisibleKeyFrames();
67 std::vector<KeyFrame*> GetBestCovisibilityKeyFrames(
const int &N);
68 std::vector<KeyFrame*> GetCovisiblesByWeight(
const int &w);
75 std::set<KeyFrame*> GetChilds();
81 std::set<KeyFrame*> GetLoopEdges();
84 void AddMapPoint(
MapPoint* pMP,
const size_t &idx);
85 void EraseMapPointMatch(
const size_t &idx);
86 void EraseMapPointMatch(
MapPoint* pMP);
87 void ReplaceMapPointMatch(
const size_t &idx,
MapPoint* pMP);
88 std::set<MapPoint*> GetMapPoints();
89 std::vector<MapPoint*> GetMapPointMatches();
90 int TrackedMapPoints(
const int &minObs);
91 MapPoint* GetMapPoint(
const size_t &idx);
94 std::vector<size_t> GetFeaturesInArea(
const float &x,
const float &y,
const float &r)
const;
95 cv::Mat UnprojectStereo(
int i);
98 bool IsInImage(
const float &x,
const float &y)
const;
109 float ComputeSceneMedianDepth(
const int q);
111 static bool weightComp(
int a,
int b){
116 return pKF1->mnId<pKF2->mnId;
123 static long unsigned int nNextId;
124 long unsigned int mnId;
125 const long unsigned int mnFrameId;
127 const double mTimeStamp;
130 const int mnGridCols;
131 const int mnGridRows;
132 const float mfGridElementWidthInv;
133 const float mfGridElementHeightInv;
136 long unsigned int mnTrackReferenceForFrame;
137 long unsigned int mnFuseTargetForKF;
140 long unsigned int mnBALocalForKF;
141 long unsigned int mnBAFixedForKF;
144 long unsigned int mnLoopQuery;
147 long unsigned int mnRelocQuery;
154 long unsigned int mnBAGlobalForKF;
157 const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth;
163 const std::vector<cv::KeyPoint> mvKeys;
164 const std::vector<cv::KeyPoint> mvKeysUn;
165 const std::vector<float> mvuRight;
166 const std::vector<float> mvDepth;
167 const cv::Mat mDescriptors;
170 DBoW2::BowVector mBowVec;
171 DBoW2::FeatureVector mFeatVec;
177 const int mnScaleLevels;
178 const float mfScaleFactor;
179 const float mfLogScaleFactor;
180 const std::vector<float> mvScaleFactors;
181 const std::vector<float> mvLevelSigma2;
182 const std::vector<float> mvInvLevelSigma2;
203 std::vector<MapPoint*> mvpMapPoints;
207 ORBVocabulary* mpORBvocabulary;
210 std::vector< std::vector <std::vector<size_t> > > mGrid;
212 std::map<KeyFrame*,int> mConnectedKeyFrameWeights;
213 std::vector<KeyFrame*> mvpOrderedConnectedKeyFrames;
214 std::vector<int> mvOrderedWeights;
217 bool mbFirstConnection;
219 std::set<KeyFrame*> mspChildrens;
220 std::set<KeyFrame*> mspLoopEdges;
231 std::mutex mMutexPose;
232 std::mutex mMutexConnections;
233 std::mutex mMutexFeatures;
Definition: KeyFrame.h:43
Definition: KeyFrameDatabase.h:42
Definition: Converter.cpp:24
Definition: MapPoint.h:39