OpenCV  3.3.0-dev
Open Source Computer Vision
Public Member Functions | Static Public Member Functions | Public Attributes | Static Public Attributes | Protected Attributes | List of all members
ORB_SLAM2::KeyFrame Class Reference

#include "KeyFrame.h"

Public Member Functions

 KeyFrame (Frame &F, Map *pMap, KeyFrameDatabase *pKFDB)
 
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_tGetFeaturesInArea (const float &x, const float &y, const float &r) const
 
std::set< KeyFrame * > GetLoopEdges ()
 
MapPointGetMapPoint (const size_t &idx)
 
std::vector< MapPoint * > GetMapPointMatches ()
 
std::set< MapPoint * > GetMapPoints ()
 
KeyFrameGetParent ()
 
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
 
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::KeyPointmvKeys
 
const std::vector< cv::KeyPointmvKeysUn
 
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
 
KeyFrameDatabasempKeyFrameDB
 
MapmpMap
 
ORBVocabularympORBvocabulary
 
KeyFramempParent
 
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
 

Constructor & Destructor Documentation

◆ KeyFrame()

ORB_SLAM2::KeyFrame::KeyFrame ( Frame F,
Map pMap,
KeyFrameDatabase pKFDB 
)

Member Function Documentation

◆ AddChild()

void ORB_SLAM2::KeyFrame::AddChild ( KeyFrame pKF)

◆ AddConnection()

void ORB_SLAM2::KeyFrame::AddConnection ( KeyFrame pKF,
const int &  weight 
)

◆ AddLoopEdge()

void ORB_SLAM2::KeyFrame::AddLoopEdge ( KeyFrame pKF)

◆ AddMapPoint()

void ORB_SLAM2::KeyFrame::AddMapPoint ( MapPoint pMP,
const size_t idx 
)

◆ ChangeParent()

void ORB_SLAM2::KeyFrame::ChangeParent ( KeyFrame pKF)

◆ ComputeBoW()

void ORB_SLAM2::KeyFrame::ComputeBoW ( )

◆ ComputeSceneMedianDepth()

float ORB_SLAM2::KeyFrame::ComputeSceneMedianDepth ( const int  q)

◆ EraseChild()

void ORB_SLAM2::KeyFrame::EraseChild ( KeyFrame pKF)

◆ EraseConnection()

void ORB_SLAM2::KeyFrame::EraseConnection ( KeyFrame pKF)

◆ EraseMapPointMatch() [1/2]

void ORB_SLAM2::KeyFrame::EraseMapPointMatch ( const size_t idx)

◆ EraseMapPointMatch() [2/2]

void ORB_SLAM2::KeyFrame::EraseMapPointMatch ( MapPoint pMP)

◆ GetBestCovisibilityKeyFrames()

std::vector<KeyFrame*> ORB_SLAM2::KeyFrame::GetBestCovisibilityKeyFrames ( const int &  N)

◆ GetCameraCenter()

cv::Mat ORB_SLAM2::KeyFrame::GetCameraCenter ( )

◆ GetChilds()

std::set<KeyFrame*> ORB_SLAM2::KeyFrame::GetChilds ( )

◆ GetConnectedKeyFrames()

std::set<KeyFrame *> ORB_SLAM2::KeyFrame::GetConnectedKeyFrames ( )

◆ GetCovisiblesByWeight()

std::vector<KeyFrame*> ORB_SLAM2::KeyFrame::GetCovisiblesByWeight ( const int &  w)

◆ GetFeaturesInArea()

std::vector<size_t> ORB_SLAM2::KeyFrame::GetFeaturesInArea ( const float &  x,
const float &  y,
const float &  r 
) const

◆ GetLoopEdges()

std::set<KeyFrame*> ORB_SLAM2::KeyFrame::GetLoopEdges ( )

◆ GetMapPoint()

MapPoint* ORB_SLAM2::KeyFrame::GetMapPoint ( const size_t idx)

◆ GetMapPointMatches()

std::vector<MapPoint*> ORB_SLAM2::KeyFrame::GetMapPointMatches ( )

◆ GetMapPoints()

std::set<MapPoint*> ORB_SLAM2::KeyFrame::GetMapPoints ( )

◆ GetParent()

KeyFrame* ORB_SLAM2::KeyFrame::GetParent ( )

◆ GetPose()

cv::Mat ORB_SLAM2::KeyFrame::GetPose ( )

◆ GetPoseInverse()

cv::Mat ORB_SLAM2::KeyFrame::GetPoseInverse ( )

◆ GetRotation()

cv::Mat ORB_SLAM2::KeyFrame::GetRotation ( )

◆ GetStereoCenter()

cv::Mat ORB_SLAM2::KeyFrame::GetStereoCenter ( )

◆ GetTranslation()

cv::Mat ORB_SLAM2::KeyFrame::GetTranslation ( )

◆ GetVectorCovisibleKeyFrames()

std::vector<KeyFrame* > ORB_SLAM2::KeyFrame::GetVectorCovisibleKeyFrames ( )

◆ GetWeight()

int ORB_SLAM2::KeyFrame::GetWeight ( KeyFrame pKF)

◆ hasChild()

bool ORB_SLAM2::KeyFrame::hasChild ( KeyFrame pKF)

◆ isBad()

bool ORB_SLAM2::KeyFrame::isBad ( )

◆ IsInImage()

bool ORB_SLAM2::KeyFrame::IsInImage ( const float &  x,
const float &  y 
) const

◆ lId()

static bool ORB_SLAM2::KeyFrame::lId ( KeyFrame pKF1,
KeyFrame pKF2 
)
inlinestatic

◆ ReplaceMapPointMatch()

void ORB_SLAM2::KeyFrame::ReplaceMapPointMatch ( const size_t idx,
MapPoint pMP 
)

◆ SetBadFlag()

void ORB_SLAM2::KeyFrame::SetBadFlag ( )

◆ SetErase()

void ORB_SLAM2::KeyFrame::SetErase ( )

◆ SetNotErase()

void ORB_SLAM2::KeyFrame::SetNotErase ( )

◆ SetPose()

void ORB_SLAM2::KeyFrame::SetPose ( const cv::Mat Tcw)

◆ TrackedMapPoints()

int ORB_SLAM2::KeyFrame::TrackedMapPoints ( const int &  minObs)

◆ UnprojectStereo()

cv::Mat ORB_SLAM2::KeyFrame::UnprojectStereo ( int  i)

◆ UpdateBestCovisibles()

void ORB_SLAM2::KeyFrame::UpdateBestCovisibles ( )

◆ UpdateConnections()

void ORB_SLAM2::KeyFrame::UpdateConnections ( )

◆ weightComp()

static bool ORB_SLAM2::KeyFrame::weightComp ( int  a,
int  b 
)
inlinestatic

Member Data Documentation

◆ Cw

cv::Mat ORB_SLAM2::KeyFrame::Cw
protected

◆ cx

const float ORB_SLAM2::KeyFrame::cx

◆ cy

const float ORB_SLAM2::KeyFrame::cy

◆ fx

const float ORB_SLAM2::KeyFrame::fx

◆ fy

const float ORB_SLAM2::KeyFrame::fy

◆ invfx

const float ORB_SLAM2::KeyFrame::invfx

◆ invfy

const float ORB_SLAM2::KeyFrame::invfy

◆ mb

const float ORB_SLAM2::KeyFrame::mb

◆ mbBad

bool ORB_SLAM2::KeyFrame::mbBad
protected

◆ mbf

const float ORB_SLAM2::KeyFrame::mbf

◆ mbFirstConnection

bool ORB_SLAM2::KeyFrame::mbFirstConnection
protected

◆ mbNotErase

bool ORB_SLAM2::KeyFrame::mbNotErase
protected

◆ mBowVec

DBoW2::BowVector ORB_SLAM2::KeyFrame::mBowVec

◆ mbToBeErased

bool ORB_SLAM2::KeyFrame::mbToBeErased
protected

◆ mConnectedKeyFrameWeights

std::map<KeyFrame*,int> ORB_SLAM2::KeyFrame::mConnectedKeyFrameWeights
protected

◆ mDescriptors

const cv::Mat ORB_SLAM2::KeyFrame::mDescriptors

◆ mFeatVec

DBoW2::FeatureVector ORB_SLAM2::KeyFrame::mFeatVec

◆ mfGridElementHeightInv

const float ORB_SLAM2::KeyFrame::mfGridElementHeightInv

◆ mfGridElementWidthInv

const float ORB_SLAM2::KeyFrame::mfGridElementWidthInv

◆ mfLogScaleFactor

const float ORB_SLAM2::KeyFrame::mfLogScaleFactor

◆ mfScaleFactor

const float ORB_SLAM2::KeyFrame::mfScaleFactor

◆ mGrid

std::vector< std::vector <std::vector<size_t> > > ORB_SLAM2::KeyFrame::mGrid
protected

◆ mHalfBaseline

float ORB_SLAM2::KeyFrame::mHalfBaseline
protected

◆ mK

const cv::Mat ORB_SLAM2::KeyFrame::mK

◆ mLoopScore

float ORB_SLAM2::KeyFrame::mLoopScore

◆ mMutexConnections

std::mutex ORB_SLAM2::KeyFrame::mMutexConnections
protected

◆ mMutexFeatures

std::mutex ORB_SLAM2::KeyFrame::mMutexFeatures
protected

◆ mMutexPose

std::mutex ORB_SLAM2::KeyFrame::mMutexPose
protected

◆ mnBAFixedForKF

long unsigned int ORB_SLAM2::KeyFrame::mnBAFixedForKF

◆ mnBAGlobalForKF

long unsigned int ORB_SLAM2::KeyFrame::mnBAGlobalForKF

◆ mnBALocalForKF

long unsigned int ORB_SLAM2::KeyFrame::mnBALocalForKF

◆ mnFrameId

const long unsigned int ORB_SLAM2::KeyFrame::mnFrameId

◆ mnFuseTargetForKF

long unsigned int ORB_SLAM2::KeyFrame::mnFuseTargetForKF

◆ mnGridCols

const int ORB_SLAM2::KeyFrame::mnGridCols

◆ mnGridRows

const int ORB_SLAM2::KeyFrame::mnGridRows

◆ mnId

long unsigned int ORB_SLAM2::KeyFrame::mnId

◆ mnLoopQuery

long unsigned int ORB_SLAM2::KeyFrame::mnLoopQuery

◆ mnLoopWords

int ORB_SLAM2::KeyFrame::mnLoopWords

◆ mnMaxX

const int ORB_SLAM2::KeyFrame::mnMaxX

◆ mnMaxY

const int ORB_SLAM2::KeyFrame::mnMaxY

◆ mnMinX

const int ORB_SLAM2::KeyFrame::mnMinX

◆ mnMinY

const int ORB_SLAM2::KeyFrame::mnMinY

◆ mnRelocQuery

long unsigned int ORB_SLAM2::KeyFrame::mnRelocQuery

◆ mnRelocWords

int ORB_SLAM2::KeyFrame::mnRelocWords

◆ mnScaleLevels

const int ORB_SLAM2::KeyFrame::mnScaleLevels

◆ mnTrackReferenceForFrame

long unsigned int ORB_SLAM2::KeyFrame::mnTrackReferenceForFrame

◆ mpKeyFrameDB

KeyFrameDatabase* ORB_SLAM2::KeyFrame::mpKeyFrameDB
protected

◆ mpMap

Map* ORB_SLAM2::KeyFrame::mpMap
protected

◆ mpORBvocabulary

ORBVocabulary* ORB_SLAM2::KeyFrame::mpORBvocabulary
protected

◆ mpParent

KeyFrame* ORB_SLAM2::KeyFrame::mpParent
protected

◆ mRelocScore

float ORB_SLAM2::KeyFrame::mRelocScore

◆ mspChildrens

std::set<KeyFrame*> ORB_SLAM2::KeyFrame::mspChildrens
protected

◆ mspLoopEdges

std::set<KeyFrame*> ORB_SLAM2::KeyFrame::mspLoopEdges
protected

◆ mTcp

cv::Mat ORB_SLAM2::KeyFrame::mTcp

◆ mTcwBefGBA

cv::Mat ORB_SLAM2::KeyFrame::mTcwBefGBA

◆ mTcwGBA

cv::Mat ORB_SLAM2::KeyFrame::mTcwGBA

◆ mThDepth

const float ORB_SLAM2::KeyFrame::mThDepth

◆ mTimeStamp

const double ORB_SLAM2::KeyFrame::mTimeStamp

◆ mvDepth

const std::vector<float> ORB_SLAM2::KeyFrame::mvDepth

◆ mvInvLevelSigma2

const std::vector<float> ORB_SLAM2::KeyFrame::mvInvLevelSigma2

◆ mvKeys

const std::vector<cv::KeyPoint> ORB_SLAM2::KeyFrame::mvKeys

◆ mvKeysUn

const std::vector<cv::KeyPoint> ORB_SLAM2::KeyFrame::mvKeysUn

◆ mvLevelSigma2

const std::vector<float> ORB_SLAM2::KeyFrame::mvLevelSigma2

◆ mvOrderedWeights

std::vector<int> ORB_SLAM2::KeyFrame::mvOrderedWeights
protected

◆ mvpMapPoints

std::vector<MapPoint*> ORB_SLAM2::KeyFrame::mvpMapPoints
protected

◆ mvpOrderedConnectedKeyFrames

std::vector<KeyFrame*> ORB_SLAM2::KeyFrame::mvpOrderedConnectedKeyFrames
protected

◆ mvScaleFactors

const std::vector<float> ORB_SLAM2::KeyFrame::mvScaleFactors

◆ mvuRight

const std::vector<float> ORB_SLAM2::KeyFrame::mvuRight

◆ N

const int ORB_SLAM2::KeyFrame::N

◆ nNextId

long unsigned int ORB_SLAM2::KeyFrame::nNextId
static

◆ Ow

cv::Mat ORB_SLAM2::KeyFrame::Ow
protected

◆ Tcw

cv::Mat ORB_SLAM2::KeyFrame::Tcw
protected

◆ Twc

cv::Mat ORB_SLAM2::KeyFrame::Twc
protected

The documentation for this class was generated from the following file: