#include <KeyFrame.h>
Public Member Functions | |
| void | AddChild (KeyFrame *pKF) |
| void | AddConnection (KeyFrame *pKF, const int &weight) |
| void | AddLoopEdge (KeyFrame *pKF) |
| void | AddMapPoint (MapPoint *pMP, const size_t &idx) |
| void | ChangeParent (KeyFrame *pKF) |
| void | ComputeBoW () |
| float | ComputeSceneMedianDepth (const int q) |
| void | EraseChild (KeyFrame *pKF) |
| void | EraseConnection (KeyFrame *pKF) |
| void | EraseMapPointMatch (const size_t &idx) |
| void | EraseMapPointMatch (MapPoint *pMP) |
| std::vector< KeyFrame * > | GetBestCovisibilityKeyFrames (const int &N) |
| cv::Mat | GetCameraCenter () |
| std::set< KeyFrame * > | GetChilds () |
| std::set< KeyFrame * > | GetConnectedKeyFrames () |
| std::vector< KeyFrame * > | GetCovisiblesByWeight (const int &w) |
| std::vector< size_t > | GetFeaturesInArea (const float &x, const float &y, const float &r) const |
| std::set< KeyFrame * > | GetLoopEdges () |
| MapPoint * | GetMapPoint (const size_t &idx) |
| std::vector< MapPoint * > | GetMapPointMatches () |
| std::set< MapPoint * > | GetMapPoints () |
| KeyFrame * | GetParent () |
| cv::Mat | GetPose () |
| cv::Mat | GetPoseInverse () |
| cv::Mat | GetRotation () |
| cv::Mat | GetStereoCenter () |
| cv::Mat | GetTranslation () |
| std::vector< KeyFrame * > | GetVectorCovisibleKeyFrames () |
| int | GetWeight (KeyFrame *pKF) |
| bool | hasChild (KeyFrame *pKF) |
| bool | isBad () |
| bool | IsInImage (const float &x, const float &y) const |
| KeyFrame (Frame &F, Map *pMap, KeyFrameDatabase *pKFDB) | |
| void | ReplaceMapPointMatch (const size_t &idx, MapPoint *pMP) |
| void | SetBadFlag () |
| void | SetErase () |
| void | SetNotErase () |
| void | SetPose (const cv::Mat &Tcw) |
| int | TrackedMapPoints (const int &minObs) |
| cv::Mat | UnprojectStereo (int i) |
| void | UpdateBestCovisibles () |
| void | UpdateConnections () |
Static Public Member Functions | |
| static bool | lId (KeyFrame *pKF1, KeyFrame *pKF2) |
| static bool | weightComp (int a, int b) |
Public Attributes | |
| const float | cx |
| const float | cy |
| const float | fx |
| const float | fy |
| const float | invfx |
| const float | invfy |
| const float | mb |
| const float | mbf |
| DBoW2::BowVector | mBowVec |
| const cv::Mat | mDescriptors |
| DBoW2::FeatureVector | mFeatVec |
| const float | mfGridElementHeightInv |
| const float | mfGridElementWidthInv |
| const float | mfLogScaleFactor |
| const float | mfScaleFactor |
| const cv::Mat | mK |
| float | mLoopScore |
| long unsigned int | mnBAFixedForKF |
| long unsigned int | mnBAGlobalForKF |
| long unsigned int | mnBALocalForKF |
| const long unsigned int | mnFrameId |
| long unsigned int | mnFuseTargetForKF |
| const int | mnGridCols |
| const int | mnGridRows |
| long unsigned int | mnId |
| long unsigned int | mnLoopQuery |
| int | mnLoopWords |
| const int | mnMaxX |
| const int | mnMaxY |
| const int | mnMinX |
| const int | mnMinY |
| long unsigned int | mnRelocQuery |
| int | mnRelocWords |
| const int | mnScaleLevels |
| long unsigned int | mnTrackReferenceForFrame |
| float | mRelocScore |
| cv::Mat | mTcp |
| cv::Mat | mTcwBefGBA |
| cv::Mat | mTcwGBA |
| const float | mThDepth |
| const double | mTimeStamp |
| const std::vector< float > | mvDepth |
| const std::vector< float > | mvInvLevelSigma2 |
| const std::vector< cv::KeyPoint > | mvKeys |
| const std::vector< cv::KeyPoint > | mvKeysUn |
| const std::vector< float > | mvLevelSigma2 |
| const std::vector< float > | mvScaleFactors |
| const std::vector< float > | mvuRight |
| const int | N |
Static Public Attributes | |
| static long unsigned int | nNextId |
Protected Attributes | |
| cv::Mat | Cw |
| bool | mbBad |
| bool | mbFirstConnection |
| bool | mbNotErase |
| bool | mbToBeErased |
| std::map< KeyFrame *, int > | mConnectedKeyFrameWeights |
| std::vector< std::vector< std::vector< size_t > > > | mGrid |
| float | mHalfBaseline |
| std::mutex | mMutexConnections |
| std::mutex | mMutexFeatures |
| std::mutex | mMutexPose |
| KeyFrameDatabase * | mpKeyFrameDB |
| Map * | mpMap |
| ORBVocabulary * | mpORBvocabulary |
| KeyFrame * | mpParent |
| std::set< KeyFrame * > | mspChildrens |
| std::set< KeyFrame * > | mspLoopEdges |
| std::vector< int > | mvOrderedWeights |
| std::vector< MapPoint * > | mvpMapPoints |
| std::vector< KeyFrame * > | mvpOrderedConnectedKeyFrames |
| cv::Mat | Ow |
| cv::Mat | Tcw |
| cv::Mat | Twc |
Definition at line 43 of file KeyFrame.h.
| ORB_SLAM2::KeyFrame::KeyFrame | ( | Frame & | F, |
| Map * | pMap, | ||
| KeyFrameDatabase * | pKFDB | ||
| ) |
| void ORB_SLAM2::KeyFrame::AddChild | ( | KeyFrame * | pKF | ) |
| void ORB_SLAM2::KeyFrame::AddConnection | ( | KeyFrame * | pKF, |
| const int & | weight | ||
| ) |
| void ORB_SLAM2::KeyFrame::AddLoopEdge | ( | KeyFrame * | pKF | ) |
| void ORB_SLAM2::KeyFrame::AddMapPoint | ( | MapPoint * | pMP, |
| const size_t & | idx | ||
| ) |
| void ORB_SLAM2::KeyFrame::ChangeParent | ( | KeyFrame * | pKF | ) |
| void ORB_SLAM2::KeyFrame::ComputeBoW | ( | ) |
| float ORB_SLAM2::KeyFrame::ComputeSceneMedianDepth | ( | const int | q | ) |
| void ORB_SLAM2::KeyFrame::EraseChild | ( | KeyFrame * | pKF | ) |
| void ORB_SLAM2::KeyFrame::EraseConnection | ( | KeyFrame * | pKF | ) |
| void ORB_SLAM2::KeyFrame::EraseMapPointMatch | ( | const size_t & | idx | ) |
| void ORB_SLAM2::KeyFrame::EraseMapPointMatch | ( | MapPoint * | pMP | ) |
| std::vector<KeyFrame*> ORB_SLAM2::KeyFrame::GetBestCovisibilityKeyFrames | ( | const int & | N | ) |
| cv::Mat ORB_SLAM2::KeyFrame::GetCameraCenter | ( | ) |
| std::vector<KeyFrame*> ORB_SLAM2::KeyFrame::GetCovisiblesByWeight | ( | const int & | w | ) |
| std::vector<size_t> ORB_SLAM2::KeyFrame::GetFeaturesInArea | ( | const float & | x, |
| const float & | y, | ||
| const float & | r | ||
| ) | const |
| MapPoint* ORB_SLAM2::KeyFrame::GetMapPoint | ( | const size_t & | idx | ) |
| std::vector<MapPoint*> ORB_SLAM2::KeyFrame::GetMapPointMatches | ( | ) |
| KeyFrame* ORB_SLAM2::KeyFrame::GetParent | ( | ) |
| cv::Mat ORB_SLAM2::KeyFrame::GetPose | ( | ) |
| cv::Mat ORB_SLAM2::KeyFrame::GetPoseInverse | ( | ) |
| cv::Mat ORB_SLAM2::KeyFrame::GetRotation | ( | ) |
| cv::Mat ORB_SLAM2::KeyFrame::GetStereoCenter | ( | ) |
| cv::Mat ORB_SLAM2::KeyFrame::GetTranslation | ( | ) |
| std::vector<KeyFrame* > ORB_SLAM2::KeyFrame::GetVectorCovisibleKeyFrames | ( | ) |
| int ORB_SLAM2::KeyFrame::GetWeight | ( | KeyFrame * | pKF | ) |
| bool ORB_SLAM2::KeyFrame::hasChild | ( | KeyFrame * | pKF | ) |
| bool ORB_SLAM2::KeyFrame::isBad | ( | ) |
| bool ORB_SLAM2::KeyFrame::IsInImage | ( | const float & | x, |
| const float & | y | ||
| ) | const |
Definition at line 114 of file KeyFrame.h.
| void ORB_SLAM2::KeyFrame::ReplaceMapPointMatch | ( | const size_t & | idx, |
| MapPoint * | pMP | ||
| ) |
| void ORB_SLAM2::KeyFrame::SetBadFlag | ( | ) |
| void ORB_SLAM2::KeyFrame::SetErase | ( | ) |
| void ORB_SLAM2::KeyFrame::SetNotErase | ( | ) |
| void ORB_SLAM2::KeyFrame::SetPose | ( | const cv::Mat & | Tcw | ) |
| int ORB_SLAM2::KeyFrame::TrackedMapPoints | ( | const int & | minObs | ) |
| cv::Mat ORB_SLAM2::KeyFrame::UnprojectStereo | ( | int | i | ) |
| void ORB_SLAM2::KeyFrame::UpdateBestCovisibles | ( | ) |
| void ORB_SLAM2::KeyFrame::UpdateConnections | ( | ) |
|
inlinestatic |
Definition at line 110 of file KeyFrame.h.
|
protected |
Definition at line 199 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::cx |
Definition at line 156 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::cy |
Definition at line 156 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::fx |
Definition at line 156 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::fy |
Definition at line 156 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::invfx |
Definition at line 156 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::invfy |
Definition at line 156 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::mb |
Definition at line 156 of file KeyFrame.h.
|
protected |
Definition at line 224 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::mbf |
Definition at line 156 of file KeyFrame.h.
|
protected |
Definition at line 216 of file KeyFrame.h.
|
protected |
Definition at line 222 of file KeyFrame.h.
| DBoW2::BowVector ORB_SLAM2::KeyFrame::mBowVec |
Definition at line 169 of file KeyFrame.h.
|
protected |
Definition at line 223 of file KeyFrame.h.
|
protected |
Definition at line 211 of file KeyFrame.h.
| const cv::Mat ORB_SLAM2::KeyFrame::mDescriptors |
Definition at line 166 of file KeyFrame.h.
| DBoW2::FeatureVector ORB_SLAM2::KeyFrame::mFeatVec |
Definition at line 170 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::mfGridElementHeightInv |
Definition at line 132 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::mfGridElementWidthInv |
Definition at line 131 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::mfLogScaleFactor |
Definition at line 178 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::mfScaleFactor |
Definition at line 177 of file KeyFrame.h.
|
protected |
Definition at line 209 of file KeyFrame.h.
|
protected |
Definition at line 226 of file KeyFrame.h.
| const cv::Mat ORB_SLAM2::KeyFrame::mK |
Definition at line 188 of file KeyFrame.h.
| float ORB_SLAM2::KeyFrame::mLoopScore |
Definition at line 145 of file KeyFrame.h.
|
protected |
Definition at line 231 of file KeyFrame.h.
|
protected |
Definition at line 232 of file KeyFrame.h.
|
protected |
Definition at line 230 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnBAFixedForKF |
Definition at line 140 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnBAGlobalForKF |
Definition at line 153 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnBALocalForKF |
Definition at line 139 of file KeyFrame.h.
| const long unsigned int ORB_SLAM2::KeyFrame::mnFrameId |
Definition at line 124 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnFuseTargetForKF |
Definition at line 136 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::mnGridCols |
Definition at line 129 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::mnGridRows |
Definition at line 130 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnId |
Definition at line 123 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnLoopQuery |
Definition at line 143 of file KeyFrame.h.
| int ORB_SLAM2::KeyFrame::mnLoopWords |
Definition at line 144 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::mnMaxX |
Definition at line 186 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::mnMaxY |
Definition at line 187 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::mnMinX |
Definition at line 184 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::mnMinY |
Definition at line 185 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnRelocQuery |
Definition at line 146 of file KeyFrame.h.
| int ORB_SLAM2::KeyFrame::mnRelocWords |
Definition at line 147 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::mnScaleLevels |
Definition at line 176 of file KeyFrame.h.
| long unsigned int ORB_SLAM2::KeyFrame::mnTrackReferenceForFrame |
Definition at line 135 of file KeyFrame.h.
|
protected |
Definition at line 205 of file KeyFrame.h.
|
protected |
Definition at line 228 of file KeyFrame.h.
|
protected |
Definition at line 206 of file KeyFrame.h.
|
protected |
Definition at line 217 of file KeyFrame.h.
| float ORB_SLAM2::KeyFrame::mRelocScore |
Definition at line 148 of file KeyFrame.h.
Definition at line 218 of file KeyFrame.h.
Definition at line 219 of file KeyFrame.h.
| cv::Mat ORB_SLAM2::KeyFrame::mTcp |
Definition at line 173 of file KeyFrame.h.
| cv::Mat ORB_SLAM2::KeyFrame::mTcwBefGBA |
Definition at line 152 of file KeyFrame.h.
| cv::Mat ORB_SLAM2::KeyFrame::mTcwGBA |
Definition at line 151 of file KeyFrame.h.
| const float ORB_SLAM2::KeyFrame::mThDepth |
Definition at line 156 of file KeyFrame.h.
| const double ORB_SLAM2::KeyFrame::mTimeStamp |
Definition at line 126 of file KeyFrame.h.
| const std::vector<float> ORB_SLAM2::KeyFrame::mvDepth |
Definition at line 165 of file KeyFrame.h.
| const std::vector<float> ORB_SLAM2::KeyFrame::mvInvLevelSigma2 |
Definition at line 181 of file KeyFrame.h.
| const std::vector<cv::KeyPoint> ORB_SLAM2::KeyFrame::mvKeys |
Definition at line 162 of file KeyFrame.h.
| const std::vector<cv::KeyPoint> ORB_SLAM2::KeyFrame::mvKeysUn |
Definition at line 163 of file KeyFrame.h.
| const std::vector<float> ORB_SLAM2::KeyFrame::mvLevelSigma2 |
Definition at line 180 of file KeyFrame.h.
|
protected |
Definition at line 213 of file KeyFrame.h.
|
protected |
Definition at line 202 of file KeyFrame.h.
|
protected |
Definition at line 212 of file KeyFrame.h.
| const std::vector<float> ORB_SLAM2::KeyFrame::mvScaleFactors |
Definition at line 179 of file KeyFrame.h.
| const std::vector<float> ORB_SLAM2::KeyFrame::mvuRight |
Definition at line 164 of file KeyFrame.h.
| const int ORB_SLAM2::KeyFrame::N |
Definition at line 159 of file KeyFrame.h.
|
static |
Definition at line 122 of file KeyFrame.h.
|
protected |
Definition at line 197 of file KeyFrame.h.
|
protected |
Definition at line 195 of file KeyFrame.h.
|
protected |
Definition at line 196 of file KeyFrame.h.