33 mfGridElementWidthInv(F.mfGridElementWidthInv), mfGridElementHeightInv(F.mfGridElementHeightInv),
34 mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0),
35 mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnBAGlobalForKF(0),
36 fx(F.fx), fy(F.fy), cx(F.cx), cy(F.cy), invfx(F.invfx), invfy(F.invfy),
37 mbf(F.mbf), mb(F.mb), mThDepth(F.mThDepth), N(F.N), mvKeys(F.mvKeys), mvKeysUn(F.mvKeysUn),
38 mvuRight(F.mvuRight), mvDepth(F.mvDepth), mDescriptors(F.mDescriptors.clone()),
39 mBowVec(F.mBowVec), mFeatVec(F.mFeatVec), mnScaleLevels(F.mnScaleLevels), mfScaleFactor(F.mfScaleFactor),
40 mfLogScaleFactor(F.mfLogScaleFactor), mvScaleFactors(F.mvScaleFactors), mvLevelSigma2(F.mvLevelSigma2),
41 mvInvLevelSigma2(F.mvInvLevelSigma2), mnMinX(F.mnMinX), mnMinY(F.mnMinY), mnMaxX(F.mnMaxX),
42 mnMaxY(F.mnMaxY), mK(F.mK), mvpMapPoints(F.mvpMapPoints), mpKeyFrameDB(pKFDB),
43 mpORBvocabulary(F.mpORBvocabulary), mbFirstConnection(true), mpParent(NULL), mbNotErase(false),
44 mbToBeErased(false), mbBad(false), mHalfBaseline(F.mb/2), mpMap(pMap)
74 cv::Mat Rcw =
Tcw.rowRange(0,3).colRange(0,3);
75 cv::Mat tcw =
Tcw.rowRange(0,3).col(3);
76 cv::Mat Rwc = Rcw.t();
79 Twc = cv::Mat::eye(4,4,
Tcw.type());
80 Rwc.copyTo(
Twc.rowRange(0,3).colRange(0,3));
81 Ow.copyTo(
Twc.rowRange(0,3).col(3));
82 cv::Mat center = (cv::Mat_<float>(4,1) <<
mHalfBaseline, 0 , 0, 1);
114 return Tcw.rowRange(0,3).colRange(0,3).clone();
120 return Tcw.rowRange(0,3).col(3).clone();
141 vector<pair<int,KeyFrame*> > vPairs;
144 vPairs.push_back(make_pair(mit->second,mit->first));
146 sort(vPairs.begin(),vPairs.end());
147 list<KeyFrame*> lKFs;
149 for(
size_t i=0, iend=vPairs.size(); i<iend;i++)
151 lKFs.push_front(vPairs[i].second);
152 lWs.push_front(vPairs[i].first);
164 s.insert(mit->first);
189 return vector<KeyFrame*>();
193 return vector<KeyFrame*>();
255 const bool bCheckObs = minObs>0;
256 for(
int i=0; i<
N; i++)
291 map<KeyFrame*,int> KFcounter;
293 vector<MapPoint*> vpMP;
302 for(vector<MapPoint*>::iterator vit=vpMP.begin(), vend=vpMP.end(); vit!=vend; vit++)
314 for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
316 if(mit->first->mnId==
mnId)
318 KFcounter[mit->first]++;
323 if(KFcounter.empty())
332 vector<pair<int,KeyFrame*> > vPairs;
333 vPairs.reserve(KFcounter.size());
334 for(map<KeyFrame*,int>::iterator mit=KFcounter.begin(), mend=KFcounter.end(); mit!=mend; mit++)
343 vPairs.push_back(make_pair(mit->second,mit->first));
350 vPairs.push_back(make_pair(nmax,pKFmax));
354 sort(vPairs.begin(),vPairs.end());
355 list<KeyFrame*> lKFs;
357 for(
size_t i=0; i<vPairs.size();i++)
359 lKFs.push_front(vPairs[i].second);
360 lWs.push_front(vPairs[i].first);
467 mit->first->EraseConnection(
this);
480 set<KeyFrame*> sParentCandidates;
487 bool bContinue =
false;
501 for(
size_t i=0, iend=vpConnected.size(); i<iend; i++)
503 for(set<KeyFrame*>::iterator spcit=sParentCandidates.begin(), spcend=sParentCandidates.end(); spcit!=spcend; spcit++)
505 if(vpConnected[i]->
mnId == (*spcit)->mnId)
523 sParentCandidates.insert(pC);
555 bool bUpdate =
false;
571 vector<size_t> vIndices;
578 const int nMaxCellX =
min((
int)
mnGridCols-1,(
int)ceil((x-
mnMinX+r)*mfGridElementWidthInv));
586 const int nMaxCellY =
min((
int)
mnGridRows-1,(
int)ceil((y-
mnMinY+r)*mfGridElementHeightInv));
590 for(
int ix = nMinCellX; ix<=nMaxCellX; ix++)
592 for(
int iy = nMinCellY; iy<=nMaxCellY; iy++)
594 const vector<size_t> vCell =
mGrid[ix][iy];
595 for(
size_t j=0, jend=vCell.size(); j<jend; j++)
597 const cv::KeyPoint &kpUn =
mvKeysUn[vCell[j]];
598 const float distx = kpUn.pt.x-x;
599 const float disty = kpUn.pt.y-y;
601 if(fabs(distx)<r && fabs(disty)<r)
602 vIndices.push_back(vCell[j]);
620 const float u =
mvKeys[i].pt.x;
621 const float v =
mvKeys[i].pt.y;
624 cv::Mat x3Dc = (cv::Mat_<float>(3,1) << x, y, z);
627 return Twc.rowRange(0,3).colRange(0,3)*x3Dc+
Twc.rowRange(0,3).col(3);
635 vector<MapPoint*> vpMapPoints;
644 vector<float> vDepths;
646 cv::Mat Rcw2 = Tcw_.row(2).colRange(0,3);
648 float zcw = Tcw_.at<
float>(2,3);
649 for(
int i=0; i<
N; i++)
655 float z = Rcw2.dot(x3Dw)+zcw;
656 vDepths.push_back(z);
660 sort(vDepths.begin(),vDepths.end());
662 return vDepths[(vDepths.size()-1)/q];
678 template<
class Archive>
684 ar &
const_cast<long unsigned int &
>(
mnFrameId);
700 ar &
const_cast<float &
>(
fx) & const_cast<float &>(
fy) &
const_cast<float &
>(
cx) & const_cast<float &>(
cy);
701 ar &
const_cast<float &
>(
invfx) & const_cast<float &>(
invfy) &
const_cast<float &
>(
mbf);
702 ar &
const_cast<float &
>(
mb) & const_cast<float &>(
mThDepth);
704 ar &
const_cast<int &
>(
N);
706 ar &
const_cast<std::vector<cv::KeyPoint> &
>(
mvKeys);
707 ar &
const_cast<std::vector<cv::KeyPoint> &
>(
mvKeysUn);
708 ar &
const_cast<std::vector<float> &
>(
mvuRight);
709 ar &
const_cast<std::vector<float> &
>(
mvDepth);
720 ar &
const_cast<cv::Mat &
>(
mK);
std::vector< KeyFrame * > GetBestCovisibilityKeyFrames(const int &N)
void serialize(Archive &ar, const unsigned int version)
void EraseMapPointMatch(const size_t &idx)
const std::vector< cv::KeyPoint > mvKeysUn
cv::Mat GetCameraCenter()
std::set< KeyFrame * > GetConnectedKeyFrames()
const std::vector< float > mvScaleFactors
std::set< KeyFrame * > mspChildrens
long unsigned int mnTrackReferenceForFrame
std::mutex mMutexFeatures
const float mfScaleFactor
void AddMapPoint(MapPoint *pMP, const size_t &idx)
cv::Mat UnprojectStereo(int i)
void erase(KeyFrame *pKF)
const std::vector< float > mvLevelSigma2
std::vector< KeyFrame * > GetCovisiblesByWeight(const int &w)
std::set< KeyFrame * > GetLoopEdges()
void ReplaceMapPointMatch(const size_t &idx, MapPoint *pMP)
long unsigned int mnBAGlobalForKF
std::vector< MapPoint * > GetMapPointMatches()
long unsigned int mnLoopQuery
std::vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r) const
long unsigned int mnRelocQuery
TFSIMD_FORCE_INLINE const tfScalar & y() const
int TrackedMapPoints(const int &minObs)
void EraseChild(KeyFrame *pKF)
std::vector< std::size_t > mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]
void EraseConnection(KeyFrame *pKF)
cv::Mat GetStereoCenter()
const std::vector< float > mvInvLevelSigma2
virtual void transform(const std::vector< TDescriptor > &features, BowVector &v) const
std::map< KeyFrame *, size_t > GetObservations()
std::vector< KeyFrame * > mvpOrderedConnectedKeyFrames
void ChangeParent(KeyFrame *pKF)
long unsigned int mnBAFixedForKF
std::vector< std::vector< std::vector< size_t > > > mGrid
const std::vector< float > mvDepth
ORBVocabulary * mpORBvocabulary
int GetWeight(KeyFrame *pKF)
bool IsInImage(const float &x, const float &y) const
static std::vector< cv::Mat > toDescriptorVector(const cv::Mat &Descriptors)
TFSIMD_FORCE_INLINE const tfScalar & x() const
long unsigned int mnFuseTargetForKF
std::set< KeyFrame * > mspLoopEdges
std::vector< int > mvOrderedWeights
const float mfGridElementHeightInv
MapPoint * GetMapPoint(const size_t &idx)
std::vector< MapPoint * > mvpMapPoints
float ComputeSceneMedianDepth(const int q)
void SetPose(const cv::Mat &Tcw)
std::vector< KeyFrame * > GetVectorCovisibleKeyFrames()
long unsigned int mnBALocalForKF
TFSIMD_FORCE_INLINE const tfScalar & z() const
void EraseKeyFrame(KeyFrame *pKF)
void AddLoopEdge(KeyFrame *pKF)
bool hasChild(KeyFrame *pKF)
TFSIMD_FORCE_INLINE const tfScalar & w() const
const std::vector< cv::KeyPoint > mvKeys
std::set< KeyFrame * > GetChilds()
DBoW2::FeatureVector mFeatVec
static long unsigned int nNextId
const std::vector< float > mvuRight
int GetIndexInKeyFrame(KeyFrame *pKF)
void AddConnection(KeyFrame *pKF, const int &weight)
std::set< MapPoint * > GetMapPoints()
static bool weightComp(int a, int b)
void UpdateBestCovisibles()
const long unsigned int mnFrameId
void AddChild(KeyFrame *pKF)
std::mutex mMutexConnections
std::map< KeyFrame *, int > mConnectedKeyFrameWeights
KeyFrameDatabase * mpKeyFrameDB
const cv::Mat mDescriptors
const float mfGridElementWidthInv
const float mfLogScaleFactor