1 Star 1 Fork 0

kindlytrees/orbslam3-with-comments

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
文件
克隆/下载
KeyFrame.cc 34.52 KB
一键复制 编辑 原始数据 按行查看 历史
kindlytrees 提交于 2025-03-01 20:17 +08:00 . update comments
12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181
/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
* License as published by the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "KeyFrame.h"
#include "Converter.h"
#include "ImuTypes.h"
#include<mutex>
namespace ORB_SLAM3
{
long unsigned int KeyFrame::nNextId=0;
KeyFrame::KeyFrame():
mnFrameId(0), mTimeStamp(0), mnGridCols(FRAME_GRID_COLS), mnGridRows(FRAME_GRID_ROWS),
mfGridElementWidthInv(0), mfGridElementHeightInv(0),
mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0), mnBALocalForMerge(0),
mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnMergeQuery(0), mnMergeWords(0), mnBAGlobalForKF(0),
fx(0), fy(0), cx(0), cy(0), invfx(0), invfy(0), mnPlaceRecognitionQuery(0), mnPlaceRecognitionWords(0), mPlaceRecognitionScore(0),
mbf(0), mb(0), mThDepth(0), N(0), mvKeys(static_cast<vector<cv::KeyPoint> >(NULL)), mvKeysUn(static_cast<vector<cv::KeyPoint> >(NULL)),
mvuRight(static_cast<vector<float> >(NULL)), mvDepth(static_cast<vector<float> >(NULL)), mnScaleLevels(0), mfScaleFactor(0),
mfLogScaleFactor(0), mvScaleFactors(0), mvLevelSigma2(0), mvInvLevelSigma2(0), mnMinX(0), mnMinY(0), mnMaxX(0),
mnMaxY(0), mPrevKF(static_cast<KeyFrame*>(NULL)), mNextKF(static_cast<KeyFrame*>(NULL)), mbFirstConnection(true), mpParent(NULL), mbNotErase(false),
mbToBeErased(false), mbBad(false), mHalfBaseline(0), mbCurrentPlaceRecognition(false), mnMergeCorrectedForKF(0),
NLeft(0),NRight(0), mnNumberOfOpt(0), mbHasVelocity(false)
{
}
KeyFrame::KeyFrame(Frame &F, Map *pMap, KeyFrameDatabase *pKFDB):
bImu(pMap->isImuInitialized()), mnFrameId(F.mnId), mTimeStamp(F.mTimeStamp), mnGridCols(FRAME_GRID_COLS), mnGridRows(FRAME_GRID_ROWS),
mfGridElementWidthInv(F.mfGridElementWidthInv), mfGridElementHeightInv(F.mfGridElementHeightInv),
mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0), mnBALocalForMerge(0),
mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnBAGlobalForKF(0), mnPlaceRecognitionQuery(0), mnPlaceRecognitionWords(0), mPlaceRecognitionScore(0),
fx(F.fx), fy(F.fy), cx(F.cx), cy(F.cy), invfx(F.invfx), invfy(F.invfy),
mbf(F.mbf), mb(F.mb), mThDepth(F.mThDepth), N(F.N), mvKeys(F.mvKeys), mvKeysUn(F.mvKeysUn),
mvuRight(F.mvuRight), mvDepth(F.mvDepth), mDescriptors(F.mDescriptors.clone()),
mBowVec(F.mBowVec), mFeatVec(F.mFeatVec), mnScaleLevels(F.mnScaleLevels), mfScaleFactor(F.mfScaleFactor),
mfLogScaleFactor(F.mfLogScaleFactor), mvScaleFactors(F.mvScaleFactors), mvLevelSigma2(F.mvLevelSigma2),
mvInvLevelSigma2(F.mvInvLevelSigma2), mnMinX(F.mnMinX), mnMinY(F.mnMinY), mnMaxX(F.mnMaxX),
mnMaxY(F.mnMaxY), mK_(F.mK_), mPrevKF(NULL), mNextKF(NULL), mpImuPreintegrated(F.mpImuPreintegrated),
mImuCalib(F.mImuCalib), mvpMapPoints(F.mvpMapPoints), mpKeyFrameDB(pKFDB),
mpORBvocabulary(F.mpORBvocabulary), mbFirstConnection(true), mpParent(NULL), mDistCoef(F.mDistCoef), mbNotErase(false), mnDataset(F.mnDataset),
mbToBeErased(false), mbBad(false), mHalfBaseline(F.mb/2), mpMap(pMap), mbCurrentPlaceRecognition(false), mNameFile(F.mNameFile), mnMergeCorrectedForKF(0),
mpCamera(F.mpCamera), mpCamera2(F.mpCamera2),
mvLeftToRightMatch(F.mvLeftToRightMatch),mvRightToLeftMatch(F.mvRightToLeftMatch), mTlr(F.GetRelativePoseTlr()),
mvKeysRight(F.mvKeysRight), NLeft(F.Nleft), NRight(F.Nright), mTrl(F.GetRelativePoseTrl()), mnNumberOfOpt(0), mbHasVelocity(false)
{
mnId=nNextId++;
mGrid.resize(mnGridCols);
if(F.Nleft != -1) mGridRight.resize(mnGridCols);
for(int i=0; i<mnGridCols;i++)
{
mGrid[i].resize(mnGridRows);
if(F.Nleft != -1) mGridRight[i].resize(mnGridRows);
for(int j=0; j<mnGridRows; j++){
mGrid[i][j] = F.mGrid[i][j];
if(F.Nleft != -1){
mGridRight[i][j] = F.mGridRight[i][j];
}
}
}
if(!F.HasVelocity()) {
mVw.setZero();
mbHasVelocity = false;
}
else
{
mVw = F.GetVelocity();
mbHasVelocity = true;
}
mImuBias = F.mImuBias;
SetPose(F.GetPose());
mnOriginMapId = pMap->GetId();
}
void KeyFrame::ComputeBoW()
{
if(mBowVec.empty() || mFeatVec.empty())
{
vector<cv::Mat> vCurrentDesc = Converter::toDescriptorVector(mDescriptors);
// Feature vector associate features with nodes in the 4th level (from leaves up)
// We assume the vocabulary tree has 6 levels, change the 4 otherwise
mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4);
}
}
void KeyFrame::SetPose(const Sophus::SE3f &Tcw)
{
unique_lock<mutex> lock(mMutexPose);
mTcw = Tcw;
mRcw = mTcw.rotationMatrix();
mTwc = mTcw.inverse();
mRwc = mTwc.rotationMatrix();
if (mImuCalib.mbIsSet) // TODO Use a flag instead of the OpenCV matrix
{
mOwb = mRwc * mImuCalib.mTcb.translation() + mTwc.translation();
}
}
void KeyFrame::SetVelocity(const Eigen::Vector3f &Vw)
{
unique_lock<mutex> lock(mMutexPose);
mVw = Vw;
mbHasVelocity = true;
}
Sophus::SE3f KeyFrame::GetPose()
{
unique_lock<mutex> lock(mMutexPose);
return mTcw;
}
Sophus::SE3f KeyFrame::GetPoseInverse()
{
unique_lock<mutex> lock(mMutexPose);
return mTwc;
}
Eigen::Vector3f KeyFrame::GetCameraCenter(){
unique_lock<mutex> lock(mMutexPose);
return mTwc.translation();
}
Eigen::Vector3f KeyFrame::GetImuPosition()
{
unique_lock<mutex> lock(mMutexPose);
return mOwb;
}
Eigen::Matrix3f KeyFrame::GetImuRotation()
{
unique_lock<mutex> lock(mMutexPose);
return (mTwc * mImuCalib.mTcb).rotationMatrix();
}
Sophus::SE3f KeyFrame::GetImuPose()
{
unique_lock<mutex> lock(mMutexPose);
return mTwc * mImuCalib.mTcb;
}
Eigen::Matrix3f KeyFrame::GetRotation(){
unique_lock<mutex> lock(mMutexPose);
return mRcw;
}
Eigen::Vector3f KeyFrame::GetTranslation()
{
unique_lock<mutex> lock(mMutexPose);
return mTcw.translation();
}
Eigen::Vector3f KeyFrame::GetVelocity()
{
unique_lock<mutex> lock(mMutexPose);
return mVw;
}
bool KeyFrame::isVelocitySet()
{
unique_lock<mutex> lock(mMutexPose);
return mbHasVelocity;
}
void KeyFrame::AddConnection(KeyFrame *pKF, const int &weight)
{
{
unique_lock<mutex> lock(mMutexConnections);
if(!mConnectedKeyFrameWeights.count(pKF))
mConnectedKeyFrameWeights[pKF]=weight;
else if(mConnectedKeyFrameWeights[pKF]!=weight)
mConnectedKeyFrameWeights[pKF]=weight;
else
return;
}
UpdateBestCovisibles();
}
void KeyFrame::UpdateBestCovisibles()
{
unique_lock<mutex> lock(mMutexConnections);
vector<pair<int,KeyFrame*> > vPairs;
vPairs.reserve(mConnectedKeyFrameWeights.size());
for(map<KeyFrame*,int>::iterator mit=mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++)
vPairs.push_back(make_pair(mit->second,mit->first));
sort(vPairs.begin(),vPairs.end());
list<KeyFrame*> lKFs;
list<int> lWs;
for(size_t i=0, iend=vPairs.size(); i<iend;i++)
{
if(!vPairs[i].second->isBad())
{
lKFs.push_front(vPairs[i].second);
lWs.push_front(vPairs[i].first);
}
}
mvpOrderedConnectedKeyFrames = vector<KeyFrame*>(lKFs.begin(),lKFs.end());
mvOrderedWeights = vector<int>(lWs.begin(), lWs.end());
}
set<KeyFrame*> KeyFrame::GetConnectedKeyFrames()
{
unique_lock<mutex> lock(mMutexConnections);
set<KeyFrame*> s;
for(map<KeyFrame*,int>::iterator mit=mConnectedKeyFrameWeights.begin();mit!=mConnectedKeyFrameWeights.end();mit++)
s.insert(mit->first);
return s;
}
vector<KeyFrame*> KeyFrame::GetVectorCovisibleKeyFrames()
{
unique_lock<mutex> lock(mMutexConnections);
return mvpOrderedConnectedKeyFrames;
}
vector<KeyFrame*> KeyFrame::GetBestCovisibilityKeyFrames(const int &N)
{
unique_lock<mutex> lock(mMutexConnections);
if((int)mvpOrderedConnectedKeyFrames.size()<N)
return mvpOrderedConnectedKeyFrames;
else
return vector<KeyFrame*>(mvpOrderedConnectedKeyFrames.begin(),mvpOrderedConnectedKeyFrames.begin()+N);
}
vector<KeyFrame*> KeyFrame::GetCovisiblesByWeight(const int &w)
{
unique_lock<mutex> lock(mMutexConnections);
if(mvpOrderedConnectedKeyFrames.empty())
{
return vector<KeyFrame*>();
}
vector<int>::iterator it = upper_bound(mvOrderedWeights.begin(),mvOrderedWeights.end(),w,KeyFrame::weightComp);
if(it==mvOrderedWeights.end() && mvOrderedWeights.back() < w)
{
return vector<KeyFrame*>();
}
else
{
int n = it-mvOrderedWeights.begin();
return vector<KeyFrame*>(mvpOrderedConnectedKeyFrames.begin(), mvpOrderedConnectedKeyFrames.begin()+n);
}
}
int KeyFrame::GetWeight(KeyFrame *pKF)
{
unique_lock<mutex> lock(mMutexConnections);
if(mConnectedKeyFrameWeights.count(pKF))
return mConnectedKeyFrameWeights[pKF];
else
return 0;
}
int KeyFrame::GetNumberMPs()
{
unique_lock<mutex> lock(mMutexFeatures);
int numberMPs = 0;
for(size_t i=0, iend=mvpMapPoints.size(); i<iend; i++)
{
if(!mvpMapPoints[i])
continue;
numberMPs++;
}
return numberMPs;
}
void KeyFrame::AddMapPoint(MapPoint *pMP, const size_t &idx)
{
unique_lock<mutex> lock(mMutexFeatures);
mvpMapPoints[idx]=pMP;
}
void KeyFrame::EraseMapPointMatch(const int &idx)
{
unique_lock<mutex> lock(mMutexFeatures);
mvpMapPoints[idx]=static_cast<MapPoint*>(NULL);
}
void KeyFrame::EraseMapPointMatch(MapPoint* pMP)
{
tuple<size_t,size_t> indexes = pMP->GetIndexInKeyFrame(this);
size_t leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
if(leftIndex != -1)
mvpMapPoints[leftIndex]=static_cast<MapPoint*>(NULL);
if(rightIndex != -1)
mvpMapPoints[rightIndex]=static_cast<MapPoint*>(NULL);
}
void KeyFrame::ReplaceMapPointMatch(const int &idx, MapPoint* pMP)
{
mvpMapPoints[idx]=pMP;
}
set<MapPoint*> KeyFrame::GetMapPoints()
{
unique_lock<mutex> lock(mMutexFeatures);
set<MapPoint*> s;
for(size_t i=0, iend=mvpMapPoints.size(); i<iend; i++)
{
if(!mvpMapPoints[i])
continue;
MapPoint* pMP = mvpMapPoints[i];
if(!pMP->isBad())
s.insert(pMP);
}
return s;
}
int KeyFrame::TrackedMapPoints(const int &minObs)
{
unique_lock<mutex> lock(mMutexFeatures);
int nPoints=0;
const bool bCheckObs = minObs>0;
for(int i=0; i<N; i++)
{
MapPoint* pMP = mvpMapPoints[i];
if(pMP)
{
if(!pMP->isBad())
{
if(bCheckObs)
{
if(mvpMapPoints[i]->Observations()>=minObs)
nPoints++;
}
else
nPoints++;
}
}
}
return nPoints;
}
vector<MapPoint*> KeyFrame::GetMapPointMatches()
{
unique_lock<mutex> lock(mMutexFeatures);
return mvpMapPoints;
}
MapPoint* KeyFrame::GetMapPoint(const size_t &idx)
{
unique_lock<mutex> lock(mMutexFeatures);
return mvpMapPoints[idx];
}
void KeyFrame::UpdateConnections(bool upParent)
{
//KFcounter:一个映射,每个KeyFrame对应一个整数,表示该关键帧与当前关键帧共享的地图点数量。
map<KeyFrame*,int> KFcounter;
//vpMP:当前关键帧的所有地图点列表。
//这段代码保证在获取地图点时,其他线程不会对其进行修改。
vector<MapPoint*> vpMP;
{
unique_lock<mutex> lockMPs(mMutexFeatures);
vpMP = mvpMapPoints;
}
//For all map points in keyframe check in which other keyframes are they seen
//Increase counter for those keyframes
//遍历当前关键帧的所有地图点。
//如果地图点无效或已被标记为坏点(isBad()),则跳过该点。
//获取该地图点的所有观测信息(即该地图点在哪些其他关键帧中也被观测到),保存在observations中。observations是一个map<KeyFrame*, tuple<int, int>>,其中每个键是一个KeyFrame,值是该关键帧中该地图点的观测信息。
for(vector<MapPoint*>::iterator vit=vpMP.begin(), vend=vpMP.end(); vit!=vend; vit++)
{
MapPoint* pMP = *vit;
if(!pMP)
continue;
if(pMP->isBad())
continue;
map<KeyFrame*,tuple<int,int>> observations = pMP->GetObservations();
//遍历该地图点的所有观测,更新每个与当前关键帧共享该地图点的其他关键帧的计数器。
//如果观测的关键帧是当前关键帧(mnId == mit->first->mnId)或者是坏的关键帧(isBad()),或者该关键帧不属于当前地图(GetMap() != mpMap),则跳过。
//否则,KFcounter[mit->first]的计数器值加1,表示当前关键帧与mit->first(其他关键帧)共享了一个地图点。
for(map<KeyFrame*,tuple<int,int>>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
{
if(mit->first->mnId==mnId || mit->first->isBad() || mit->first->GetMap() != mpMap)
continue;
KFcounter[mit->first]++;
}
}
// This should not happen
if(KFcounter.empty())
return;
//If the counter is greater than threshold add connection
//In case no keyframe counter is over threshold add the one with maximum counter
int nmax=0;
KeyFrame* pKFmax=NULL;
int th = 15;
//nmax和pKFmax用来记录具有最大共享地图点数的关键帧。
//th是一个阈值,只有当一个关键帧与当前关键帧共享的地图点数超过此阈值时,才会被认为是有效的连接。
//vPairs用来保存符合条件的关键帧和它们的共享点数。
vector<pair<int,KeyFrame*> > vPairs;
vPairs.reserve(KFcounter.size());
if(!upParent)
cout << "UPDATE_CONN: current KF " << mnId << endl;
//遍历KFcounter,如果当前计数值大于最大值nmax,则更新nmax和pKFmax。
//如果某个关键帧与当前关键帧共享的地图点数大于等于阈值th,则添加到vPairs中,并通过AddConnection方法建立连接。
for(map<KeyFrame*,int>::iterator mit=KFcounter.begin(), mend=KFcounter.end(); mit!=mend; mit++)
{
if(!upParent)
cout << " UPDATE_CONN: KF " << mit->first->mnId << " ; num matches: " << mit->second << endl;
if(mit->second>nmax)
{
nmax=mit->second;
pKFmax=mit->first;
}
if(mit->second>=th)
{
vPairs.push_back(make_pair(mit->second,mit->first));
(mit->first)->AddConnection(this,mit->second);//更新共视关键帧中的相关的连接信息和权重信息
}
}
//如果没有任何关键帧的共享地图点数超过阈值th,则选择共享地图点最多的关键帧pKFmax,并建立连接。
if(vPairs.empty())
{
vPairs.push_back(make_pair(nmax,pKFmax));
pKFmax->AddConnection(this,nmax);
}
//对vPairs按照共享地图点数进行排序。
//将排序后的关键帧和其对应的共享点数保存到lKFs和lWs中。
sort(vPairs.begin(),vPairs.end());
list<KeyFrame*> lKFs;
list<int> lWs;
for(size_t i=0; i<vPairs.size();i++)
{
lKFs.push_front(vPairs[i].second);
lWs.push_front(vPairs[i].first);
}
{
//使用锁更新当前关键帧的连接信息,确保线程安全。
//更新当前关键帧的连接权重和连接的关键帧列表。
unique_lock<mutex> lockCon(mMutexConnections);
mConnectedKeyFrameWeights = KFcounter;
mvpOrderedConnectedKeyFrames = vector<KeyFrame*>(lKFs.begin(),lKFs.end());
mvOrderedWeights = vector<int>(lWs.begin(), lWs.end());
//如果这是当前关键帧的第一次连接,并且当前关键帧不是地图的初始化关键帧,则设置其父关键帧(mpParent)为与其共享最多地图点的关键帧,并建立双向连接(父子关系)。
if(mbFirstConnection && mnId!=mpMap->GetInitKFid())
{
mpParent = mvpOrderedConnectedKeyFrames.front();
mpParent->AddChild(this);
mbFirstConnection = false;
}
}
}
void KeyFrame::AddChild(KeyFrame *pKF)
{
unique_lock<mutex> lockCon(mMutexConnections);
mspChildrens.insert(pKF);
}
void KeyFrame::EraseChild(KeyFrame *pKF)
{
unique_lock<mutex> lockCon(mMutexConnections);
mspChildrens.erase(pKF);
}
void KeyFrame::ChangeParent(KeyFrame *pKF)
{
unique_lock<mutex> lockCon(mMutexConnections);
if(pKF == this)
{
cout << "ERROR: Change parent KF, the parent and child are the same KF" << endl;
throw std::invalid_argument("The parent and child can not be the same");
}
mpParent = pKF;
pKF->AddChild(this);
}
set<KeyFrame*> KeyFrame::GetChilds()
{
unique_lock<mutex> lockCon(mMutexConnections);
return mspChildrens;
}
KeyFrame* KeyFrame::GetParent()
{
unique_lock<mutex> lockCon(mMutexConnections);
return mpParent;
}
bool KeyFrame::hasChild(KeyFrame *pKF)
{
unique_lock<mutex> lockCon(mMutexConnections);
return mspChildrens.count(pKF);
}
void KeyFrame::SetFirstConnection(bool bFirst)
{
unique_lock<mutex> lockCon(mMutexConnections);
mbFirstConnection=bFirst;
}
void KeyFrame::AddLoopEdge(KeyFrame *pKF)
{
unique_lock<mutex> lockCon(mMutexConnections);
mbNotErase = true;
mspLoopEdges.insert(pKF);
}
set<KeyFrame*> KeyFrame::GetLoopEdges()
{
unique_lock<mutex> lockCon(mMutexConnections);
return mspLoopEdges;
}
void KeyFrame::AddMergeEdge(KeyFrame* pKF)
{
unique_lock<mutex> lockCon(mMutexConnections);
mbNotErase = true;
mspMergeEdges.insert(pKF);
}
set<KeyFrame*> KeyFrame::GetMergeEdges()
{
unique_lock<mutex> lockCon(mMutexConnections);
return mspMergeEdges;
}
void KeyFrame::SetNotErase()
{
unique_lock<mutex> lock(mMutexConnections);
mbNotErase = true;
}
void KeyFrame::SetErase()
{
{
unique_lock<mutex> lock(mMutexConnections);
if(mspLoopEdges.empty())
{
mbNotErase = false;
}
}
if(mbToBeErased)
{
SetBadFlag();
}
}
void KeyFrame::SetBadFlag()
{
{
unique_lock<mutex> lock(mMutexConnections);
if(mnId==mpMap->GetInitKFid())
{
return;
}
else if(mbNotErase)
{
mbToBeErased = true;
return;
}
}
for(map<KeyFrame*,int>::iterator mit = mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++)
{
mit->first->EraseConnection(this);
}
for(size_t i=0; i<mvpMapPoints.size(); i++)
{
if(mvpMapPoints[i])
{
mvpMapPoints[i]->EraseObservation(this);
}
}
{
unique_lock<mutex> lock(mMutexConnections);
unique_lock<mutex> lock1(mMutexFeatures);
mConnectedKeyFrameWeights.clear();
mvpOrderedConnectedKeyFrames.clear();
// Update Spanning Tree
set<KeyFrame*> sParentCandidates;
if(mpParent)
sParentCandidates.insert(mpParent);
// Assign at each iteration one children with a parent (the pair with highest covisibility weight)
// Include that children as new parent candidate for the rest
while(!mspChildrens.empty())
{
bool bContinue = false;
int max = -1;
KeyFrame* pC;
KeyFrame* pP;
for(set<KeyFrame*>::iterator sit=mspChildrens.begin(), send=mspChildrens.end(); sit!=send; sit++)
{
KeyFrame* pKF = *sit;
if(pKF->isBad())
continue;
// Check if a parent candidate is connected to the keyframe
vector<KeyFrame*> vpConnected = pKF->GetVectorCovisibleKeyFrames();
for(size_t i=0, iend=vpConnected.size(); i<iend; i++)
{
for(set<KeyFrame*>::iterator spcit=sParentCandidates.begin(), spcend=sParentCandidates.end(); spcit!=spcend; spcit++)
{
if(vpConnected[i]->mnId == (*spcit)->mnId)
{
int w = pKF->GetWeight(vpConnected[i]);
if(w>max)
{
pC = pKF;
pP = vpConnected[i];
max = w;
bContinue = true;
}
}
}
}
}
if(bContinue)
{
pC->ChangeParent(pP);
sParentCandidates.insert(pC);
mspChildrens.erase(pC);
}
else
break;
}
// If a children has no covisibility links with any parent candidate, assign to the original parent of this KF
if(!mspChildrens.empty())
{
for(set<KeyFrame*>::iterator sit=mspChildrens.begin(); sit!=mspChildrens.end(); sit++)
{
(*sit)->ChangeParent(mpParent);
}
}
if(mpParent){
mpParent->EraseChild(this);
mTcp = mTcw * mpParent->GetPoseInverse();
}
mbBad = true;
}
mpMap->EraseKeyFrame(this);
mpKeyFrameDB->erase(this);
}
bool KeyFrame::isBad()
{
unique_lock<mutex> lock(mMutexConnections);
return mbBad;
}
void KeyFrame::EraseConnection(KeyFrame* pKF)
{
bool bUpdate = false;
{
unique_lock<mutex> lock(mMutexConnections);
if(mConnectedKeyFrameWeights.count(pKF))
{
mConnectedKeyFrameWeights.erase(pKF);
bUpdate=true;
}
}
if(bUpdate)
UpdateBestCovisibles();
}
vector<size_t> KeyFrame::GetFeaturesInArea(const float &x, const float &y, const float &r, const bool bRight) const
{
vector<size_t> vIndices;
vIndices.reserve(N);
float factorX = r;
float factorY = r;
const int nMinCellX = max(0,(int)floor((x-mnMinX-factorX)*mfGridElementWidthInv));
if(nMinCellX>=mnGridCols)
return vIndices;
const int nMaxCellX = min((int)mnGridCols-1,(int)ceil((x-mnMinX+factorX)*mfGridElementWidthInv));
if(nMaxCellX<0)
return vIndices;
const int nMinCellY = max(0,(int)floor((y-mnMinY-factorY)*mfGridElementHeightInv));
if(nMinCellY>=mnGridRows)
return vIndices;
const int nMaxCellY = min((int)mnGridRows-1,(int)ceil((y-mnMinY+factorY)*mfGridElementHeightInv));
if(nMaxCellY<0)
return vIndices;
for(int ix = nMinCellX; ix<=nMaxCellX; ix++)
{
for(int iy = nMinCellY; iy<=nMaxCellY; iy++)
{
const vector<size_t> vCell = (!bRight) ? mGrid[ix][iy] : mGridRight[ix][iy];
for(size_t j=0, jend=vCell.size(); j<jend; j++)
{
const cv::KeyPoint &kpUn = (NLeft == -1) ? mvKeysUn[vCell[j]]
: (!bRight) ? mvKeys[vCell[j]]
: mvKeysRight[vCell[j]];
const float distx = kpUn.pt.x-x;
const float disty = kpUn.pt.y-y;
if(fabs(distx)<r && fabs(disty)<r)
vIndices.push_back(vCell[j]);
}
}
}
return vIndices;
}
bool KeyFrame::IsInImage(const float &x, const float &y) const
{
return (x>=mnMinX && x<mnMaxX && y>=mnMinY && y<mnMaxY);
}
bool KeyFrame::UnprojectStereo(int i, Eigen::Vector3f &x3D)
{
const float z = mvDepth[i];
if(z>0)
{
const float u = mvKeys[i].pt.x;
const float v = mvKeys[i].pt.y;
const float x = (u-cx)*z*invfx;
const float y = (v-cy)*z*invfy;
Eigen::Vector3f x3Dc(x, y, z);
unique_lock<mutex> lock(mMutexPose);
x3D = mRwc * x3Dc + mTwc.translation();
return true;
}
else
return false;
}
float KeyFrame::ComputeSceneMedianDepth(const int q)
{
if(N==0)
return -1.0;
vector<MapPoint*> vpMapPoints;
Eigen::Matrix3f Rcw;
Eigen::Vector3f tcw;
{
unique_lock<mutex> lock(mMutexFeatures);
unique_lock<mutex> lock2(mMutexPose);
vpMapPoints = mvpMapPoints;
tcw = mTcw.translation();
Rcw = mRcw;
}
vector<float> vDepths;
vDepths.reserve(N);
Eigen::Matrix<float,1,3> Rcw2 = Rcw.row(2);
float zcw = tcw(2);
for(int i=0; i<N; i++) {
if(mvpMapPoints[i])
{
MapPoint* pMP = mvpMapPoints[i];
Eigen::Vector3f x3Dw = pMP->GetWorldPos();
float z = Rcw2.dot(x3Dw) + zcw;
vDepths.push_back(z);
}
}
sort(vDepths.begin(),vDepths.end());
return vDepths[(vDepths.size()-1)/q];
}
void KeyFrame::SetNewBias(const IMU::Bias &b)
{
unique_lock<mutex> lock(mMutexPose);
mImuBias = b;
if(mpImuPreintegrated)
mpImuPreintegrated->SetNewBias(b);
}
Eigen::Vector3f KeyFrame::GetGyroBias()
{
unique_lock<mutex> lock(mMutexPose);
return Eigen::Vector3f(mImuBias.bwx, mImuBias.bwy, mImuBias.bwz);
}
Eigen::Vector3f KeyFrame::GetAccBias()
{
unique_lock<mutex> lock(mMutexPose);
return Eigen::Vector3f(mImuBias.bax, mImuBias.bay, mImuBias.baz);
}
IMU::Bias KeyFrame::GetImuBias()
{
unique_lock<mutex> lock(mMutexPose);
return mImuBias;
}
Map* KeyFrame::GetMap()
{
unique_lock<mutex> lock(mMutexMap);
return mpMap;
}
void KeyFrame::UpdateMap(Map* pMap)
{
unique_lock<mutex> lock(mMutexMap);
mpMap = pMap;
}
void KeyFrame::PreSave(set<KeyFrame*>& spKF,set<MapPoint*>& spMP, set<GeometricCamera*>& spCam)
{
// Save the id of each MapPoint in this KF, there can be null pointer in the vector
mvBackupMapPointsId.clear();
mvBackupMapPointsId.reserve(N);
for(int i = 0; i < N; ++i)
{
if(mvpMapPoints[i] && spMP.find(mvpMapPoints[i]) != spMP.end()) // Checks if the element is not null
mvBackupMapPointsId.push_back(mvpMapPoints[i]->mnId);
else // If the element is null his value is -1 because all the id are positives
mvBackupMapPointsId.push_back(-1);
}
// Save the id of each connected KF with it weight
mBackupConnectedKeyFrameIdWeights.clear();
for(std::map<KeyFrame*,int>::const_iterator it = mConnectedKeyFrameWeights.begin(), end = mConnectedKeyFrameWeights.end(); it != end; ++it)
{
if(spKF.find(it->first) != spKF.end())
mBackupConnectedKeyFrameIdWeights[it->first->mnId] = it->second;
}
// Save the parent id
mBackupParentId = -1;
if(mpParent && spKF.find(mpParent) != spKF.end())
mBackupParentId = mpParent->mnId;
// Save the id of the childrens KF
mvBackupChildrensId.clear();
mvBackupChildrensId.reserve(mspChildrens.size());
for(KeyFrame* pKFi : mspChildrens)
{
if(spKF.find(pKFi) != spKF.end())
mvBackupChildrensId.push_back(pKFi->mnId);
}
// Save the id of the loop edge KF
mvBackupLoopEdgesId.clear();
mvBackupLoopEdgesId.reserve(mspLoopEdges.size());
for(KeyFrame* pKFi : mspLoopEdges)
{
if(spKF.find(pKFi) != spKF.end())
mvBackupLoopEdgesId.push_back(pKFi->mnId);
}
// Save the id of the merge edge KF
mvBackupMergeEdgesId.clear();
mvBackupMergeEdgesId.reserve(mspMergeEdges.size());
for(KeyFrame* pKFi : mspMergeEdges)
{
if(spKF.find(pKFi) != spKF.end())
mvBackupMergeEdgesId.push_back(pKFi->mnId);
}
//Camera data
mnBackupIdCamera = -1;
if(mpCamera && spCam.find(mpCamera) != spCam.end())
mnBackupIdCamera = mpCamera->GetId();
mnBackupIdCamera2 = -1;
if(mpCamera2 && spCam.find(mpCamera2) != spCam.end())
mnBackupIdCamera2 = mpCamera2->GetId();
//Inertial data
mBackupPrevKFId = -1;
if(mPrevKF && spKF.find(mPrevKF) != spKF.end())
mBackupPrevKFId = mPrevKF->mnId;
mBackupNextKFId = -1;
if(mNextKF && spKF.find(mNextKF) != spKF.end())
mBackupNextKFId = mNextKF->mnId;
if(mpImuPreintegrated)
mBackupImuPreintegrated.CopyFrom(mpImuPreintegrated);
}
void KeyFrame::PostLoad(map<long unsigned int, KeyFrame*>& mpKFid, map<long unsigned int, MapPoint*>& mpMPid, map<unsigned int, GeometricCamera*>& mpCamId){
// Rebuild the empty variables
// Pose
SetPose(mTcw);
mTrl = mTlr.inverse();
// Reference reconstruction
// Each MapPoint sight from this KeyFrame
mvpMapPoints.clear();
mvpMapPoints.resize(N);
for(int i=0; i<N; ++i)
{
if(mvBackupMapPointsId[i] != -1)
mvpMapPoints[i] = mpMPid[mvBackupMapPointsId[i]];
else
mvpMapPoints[i] = static_cast<MapPoint*>(NULL);
}
// Conected KeyFrames with him weight
mConnectedKeyFrameWeights.clear();
for(map<long unsigned int, int>::const_iterator it = mBackupConnectedKeyFrameIdWeights.begin(), end = mBackupConnectedKeyFrameIdWeights.end();
it != end; ++it)
{
KeyFrame* pKFi = mpKFid[it->first];
mConnectedKeyFrameWeights[pKFi] = it->second;
}
// Restore parent KeyFrame
if(mBackupParentId>=0)
mpParent = mpKFid[mBackupParentId];
// KeyFrame childrens
mspChildrens.clear();
for(vector<long unsigned int>::const_iterator it = mvBackupChildrensId.begin(), end = mvBackupChildrensId.end(); it!=end; ++it)
{
mspChildrens.insert(mpKFid[*it]);
}
// Loop edge KeyFrame
mspLoopEdges.clear();
for(vector<long unsigned int>::const_iterator it = mvBackupLoopEdgesId.begin(), end = mvBackupLoopEdgesId.end(); it != end; ++it)
{
mspLoopEdges.insert(mpKFid[*it]);
}
// Merge edge KeyFrame
mspMergeEdges.clear();
for(vector<long unsigned int>::const_iterator it = mvBackupMergeEdgesId.begin(), end = mvBackupMergeEdgesId.end(); it != end; ++it)
{
mspMergeEdges.insert(mpKFid[*it]);
}
//Camera data
if(mnBackupIdCamera >= 0)
{
mpCamera = mpCamId[mnBackupIdCamera];
}
else
{
cout << "ERROR: There is not a main camera in KF " << mnId << endl;
}
if(mnBackupIdCamera2 >= 0)
{
mpCamera2 = mpCamId[mnBackupIdCamera2];
}
//Inertial data
if(mBackupPrevKFId != -1)
{
mPrevKF = mpKFid[mBackupPrevKFId];
}
if(mBackupNextKFId != -1)
{
mNextKF = mpKFid[mBackupNextKFId];
}
mpImuPreintegrated = &mBackupImuPreintegrated;
// Remove all backup container
mvBackupMapPointsId.clear();
mBackupConnectedKeyFrameIdWeights.clear();
mvBackupChildrensId.clear();
mvBackupLoopEdgesId.clear();
UpdateBestCovisibles();
}
bool KeyFrame::ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v)
{
// 3D in absolute coordinates
Eigen::Vector3f P = pMP->GetWorldPos();
// 3D in camera coordinates
Eigen::Vector3f Pc = mRcw * P + mTcw.translation();
float &PcX = Pc(0);
float &PcY = Pc(1);
float &PcZ = Pc(2);
// Check positive depth
if(PcZ<0.0f)
{
cout << "Negative depth: " << PcZ << endl;
return false;
}
// Project in image and check it is not outside
float invz = 1.0f/PcZ;
u=fx*PcX*invz+cx;
v=fy*PcY*invz+cy;
// cout << "c";
if(u<mnMinX || u>mnMaxX)
return false;
if(v<mnMinY || v>mnMaxY)
return false;
float x = (u - cx) * invfx;
float y = (v - cy) * invfy;
float r2 = x * x + y * y;
float k1 = mDistCoef.at<float>(0);
float k2 = mDistCoef.at<float>(1);
float p1 = mDistCoef.at<float>(2);
float p2 = mDistCoef.at<float>(3);
float k3 = 0;
if(mDistCoef.total() == 5)
{
k3 = mDistCoef.at<float>(4);
}
// Radial distorsion
float x_distort = x * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2);
float y_distort = y * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2);
// Tangential distorsion
x_distort = x_distort + (2 * p1 * x * y + p2 * (r2 + 2 * x * x));
y_distort = y_distort + (p1 * (r2 + 2 * y * y) + 2 * p2 * x * y);
float u_distort = x_distort * fx + cx;
float v_distort = y_distort * fy + cy;
u = u_distort;
v = v_distort;
kp = cv::Point2f(u, v);
return true;
}
bool KeyFrame::ProjectPointUnDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v)
{
// 3D in absolute coordinates
Eigen::Vector3f P = pMP->GetWorldPos();
// 3D in camera coordinates
Eigen::Vector3f Pc = mRcw * P + mTcw.translation();
float &PcX = Pc(0);
float &PcY= Pc(1);
float &PcZ = Pc(2);
// Check positive depth
if(PcZ<0.0f)
{
cout << "Negative depth: " << PcZ << endl;
return false;
}
// Project in image and check it is not outside
const float invz = 1.0f/PcZ;
u = fx * PcX * invz + cx;
v = fy * PcY * invz + cy;
if(u<mnMinX || u>mnMaxX)
return false;
if(v<mnMinY || v>mnMaxY)
return false;
kp = cv::Point2f(u, v);
return true;
}
Sophus::SE3f KeyFrame::GetRelativePoseTrl()
{
unique_lock<mutex> lock(mMutexPose);
return mTrl;
}
Sophus::SE3f KeyFrame::GetRelativePoseTlr()
{
unique_lock<mutex> lock(mMutexPose);
return mTlr;
}
Sophus::SE3<float> KeyFrame::GetRightPose() {
unique_lock<mutex> lock(mMutexPose);
return mTrl * mTcw;
}
Sophus::SE3<float> KeyFrame::GetRightPoseInverse() {
unique_lock<mutex> lock(mMutexPose);
return mTwc * mTlr;
}
Eigen::Vector3f KeyFrame::GetRightCameraCenter() {
unique_lock<mutex> lock(mMutexPose);
return (mTwc * mTlr).translation();
}
Eigen::Matrix<float,3,3> KeyFrame::GetRightRotation() {
unique_lock<mutex> lock(mMutexPose);
return (mTrl.so3() * mTcw.so3()).matrix();
}
Eigen::Vector3f KeyFrame::GetRightTranslation() {
unique_lock<mutex> lock(mMutexPose);
return (mTrl * mTcw).translation();
}
void KeyFrame::SetORBVocabulary(ORBVocabulary* pORBVoc)
{
mpORBvocabulary = pORBVoc;
}
void KeyFrame::SetKeyFrameDatabase(KeyFrameDatabase* pKFDB)
{
mpKeyFrameDB = pKFDB;
}
} //namespace ORB_SLAM
Loading...
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
1
https://gitee.com/kindlytree/orbslam3-with-comments.git
git@gitee.com:kindlytree/orbslam3-with-comments.git
kindlytree
orbslam3-with-comments
orbslam3-with-comments
master

搜索帮助