orb_slam3_details/src/KeyFrame.cc

1321 lines
44 KiB
C++
Raw Normal View History

2020-12-01 11:58:17 +08:00
/**
2022-03-28 21:20:28 +08:00
* 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/>.
*/
2020-12-01 11:58:17 +08:00
#include "KeyFrame.h"
#include "Converter.h"
#include "ImuTypes.h"
2022-03-28 21:20:28 +08:00
#include <mutex>
2020-12-01 11:58:17 +08:00
namespace ORB_SLAM3
{
2022-03-28 21:20:28 +08:00
long unsigned int KeyFrame::nNextId = 0;
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
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)
2020-12-01 11:58:17 +08:00
{
}
2022-03-28 21:20:28 +08:00
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),
2020-12-01 11:58:17 +08:00
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),
2022-03-28 21:20:28 +08:00
mnMaxY(F.mnMaxY), mK_(F.mK_), mPrevKF(NULL), mNextKF(NULL), mpImuPreintegrated(F.mpImuPreintegrated),
2020-12-01 11:58:17 +08:00
mImuCalib(F.mImuCalib), mvpMapPoints(F.mvpMapPoints), mpKeyFrameDB(pKFDB),
mpORBvocabulary(F.mpORBvocabulary), mbFirstConnection(true), mpParent(NULL), mDistCoef(F.mDistCoef), mbNotErase(false), mnDataset(F.mnDataset),
2022-03-28 21:20:28 +08:00
mbToBeErased(false), mbBad(false), mHalfBaseline(F.mb / 2), mpMap(pMap), mbCurrentPlaceRecognition(false), mNameFile(F.mNameFile), mnMergeCorrectedForKF(0),
2020-12-01 11:58:17 +08:00
mpCamera(F.mpCamera), mpCamera2(F.mpCamera2),
2022-03-28 21:20:28 +08:00
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)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
mnId = nNextId++;
2020-12-01 11:58:17 +08:00
// 根据指定的普通帧, 初始化用于加速匹配的网格对象信息; 其实就把每个网格中有的特征点的索引复制过来
mGrid.resize(mnGridCols);
2022-03-28 21:20:28 +08:00
if (F.Nleft != -1)
mGridRight.resize(mnGridCols);
for (int i = 0; i < mnGridCols; i++)
2020-12-01 11:58:17 +08:00
{
mGrid[i].resize(mnGridRows);
2022-03-28 21:20:28 +08:00
if (F.Nleft != -1)
mGridRight[i].resize(mnGridRows);
for (int j = 0; j < mnGridRows; j++)
{
2020-12-01 11:58:17 +08:00
mGrid[i][j] = F.mGrid[i][j];
2022-03-28 21:20:28 +08:00
if (F.Nleft != -1)
{
2020-12-01 11:58:17 +08:00
mGridRight[i][j] = F.mGridRight[i][j];
}
}
}
2022-03-28 21:20:28 +08:00
if (!F.HasVelocity())
{
mVw.setZero();
mbHasVelocity = false;
}
2020-12-01 11:58:17 +08:00
else
2022-03-28 21:20:28 +08:00
{
mVw = F.GetVelocity();
mbHasVelocity = true;
}
2020-12-01 11:58:17 +08:00
mImuBias = F.mImuBias;
2022-03-28 21:20:28 +08:00
SetPose(F.GetPose());
2020-12-01 11:58:17 +08:00
mnOriginMapId = pMap->GetId();
}
void KeyFrame::ComputeBoW()
{
// 只有当词袋向量或者节点和特征序号的特征向量为空的时候执行
2022-03-28 21:20:28 +08:00
if (mBowVec.empty() || mFeatVec.empty())
2020-12-01 11:58:17 +08:00
{
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
2022-03-28 21:20:28 +08:00
mpORBvocabulary->transform(vCurrentDesc, mBowVec, mFeatVec, 4);
2020-12-01 11:58:17 +08:00
}
}
// 设置当前关键帧的位姿
2022-03-28 21:20:28 +08:00
void KeyFrame::SetPose(const Sophus::SE3f &Tcw)
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
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)
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
mVw = Vw;
mbHasVelocity = true;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
// 获取位姿
Sophus::SE3f KeyFrame::GetPose()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTcw;
2020-12-01 11:58:17 +08:00
}
// 获取位姿的逆
2022-03-28 21:20:28 +08:00
Sophus::SE3f KeyFrame::GetPoseInverse()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTwc;
2020-12-01 11:58:17 +08:00
}
// 获取(左目)相机的中心在世界坐标系下的坐标
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetCameraCenter()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTwc.translation();
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetImuPosition()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mOwb;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Matrix3f KeyFrame::GetImuRotation()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return (mTwc * mImuCalib.mTcb).rotationMatrix();
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Sophus::SE3f KeyFrame::GetImuPose()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTwc * mImuCalib.mTcb;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Matrix3f KeyFrame::GetRotation()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mRcw;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetTranslation()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTcw.translation();
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetVelocity()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mVw;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
bool KeyFrame::isVelocitySet()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mbHasVelocity;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
2020-12-01 11:58:17 +08:00
// 为关键帧之间添加或更新连接
void KeyFrame::AddConnection(KeyFrame *pKF, const int &weight)
{
{
// 如果被占用就一直等着,这个添加连接的操作不能够被放弃
unique_lock<mutex> lock(mMutexConnections);
// 判断当前关键帧是否已经和其他的关键帧创建了联系
// std::map::count函数只可能返回0或1两种情况
2022-03-28 21:20:28 +08:00
// count函数返回0mConnectedKeyFrameWeights中没有pKF之前没有连接
if (!mConnectedKeyFrameWeights.count(pKF))
mConnectedKeyFrameWeights[pKF] = weight;
else if (mConnectedKeyFrameWeights[pKF] != weight) // 之前连接的权重不一样,更新
mConnectedKeyFrameWeights[pKF] = weight;
2020-12-01 11:58:17 +08:00
else
return;
}
// 如果添加了更新的连接关系就要更新一下,主要是重新进行排序
UpdateBestCovisibles();
}
/**
* @brief
*
* mvpOrderedConnectedKeyFramesmvOrderedWeights
*/
void KeyFrame::UpdateBestCovisibles()
{
unique_lock<mutex> lock(mMutexConnections);
2022-03-28 21:20:28 +08:00
vector<pair<int, KeyFrame *>> vPairs;
2020-12-01 11:58:17 +08:00
vPairs.reserve(mConnectedKeyFrameWeights.size());
// 取出所有连接的关键帧mConnectedKeyFrameWeights的类型为std::map<KeyFrame*,int>而vPairs变量将共视的3D点数放在前面利于排序
2022-03-28 21:20:28 +08:00
for (map<KeyFrame *, int>::iterator mit = mConnectedKeyFrameWeights.begin(), mend = mConnectedKeyFrameWeights.end(); mit != mend; mit++)
vPairs.push_back(make_pair(mit->second, mit->first));
2020-12-01 11:58:17 +08:00
// 按照权重进行排序(默认是从小到大)
2022-03-28 21:20:28 +08:00
sort(vPairs.begin(), vPairs.end());
2020-12-01 11:58:17 +08:00
// 为什么要用链表保存?因为插入和删除操作方便,只需要修改上一节点位置,不需要移动其他元素
2022-03-28 21:20:28 +08:00
list<KeyFrame *> lKFs;
list<int> lWs;
for (size_t i = 0, iend = vPairs.size(); i < iend; i++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (!vPairs[i].second->isBad())
2021-08-09 19:34:51 +08:00
{
2022-03-28 21:20:28 +08:00
// push_front 后变成从大到小
2021-08-09 19:34:51 +08:00
lKFs.push_front(vPairs[i].second);
lWs.push_front(vPairs[i].first);
}
2020-12-01 11:58:17 +08:00
}
// 权重从大到小
2022-03-28 21:20:28 +08:00
mvpOrderedConnectedKeyFrames = vector<KeyFrame *>(lKFs.begin(), lKFs.end());
2020-12-01 11:58:17 +08:00
mvOrderedWeights = vector<int>(lWs.begin(), lWs.end());
}
// 得到与该关键帧连接(>15个共视地图点的关键帧(没有排序的)
2022-03-28 21:20:28 +08:00
set<KeyFrame *> KeyFrame::GetConnectedKeyFrames()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexConnections);
2022-03-28 21:20:28 +08:00
set<KeyFrame *> s;
for (map<KeyFrame *, int>::iterator mit = mConnectedKeyFrameWeights.begin(); mit != mConnectedKeyFrameWeights.end(); mit++)
2020-12-01 11:58:17 +08:00
s.insert(mit->first);
return s;
}
// 得到与该关键帧连接的关键帧(已按权值排序)
2022-03-28 21:20:28 +08:00
vector<KeyFrame *> KeyFrame::GetVectorCovisibleKeyFrames()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexConnections);
return mvpOrderedConnectedKeyFrames;
}
// 得到与该关键帧连接的前N个关键帧(已按权值排序)
2022-03-28 21:20:28 +08:00
vector<KeyFrame *> KeyFrame::GetBestCovisibilityKeyFrames(const int &N)
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexConnections);
2022-03-28 21:20:28 +08:00
// 如果不够达到的数目就直接吧现在所有的关键帧都返回了
if ((int)mvpOrderedConnectedKeyFrames.size() < N)
2020-12-01 11:58:17 +08:00
return mvpOrderedConnectedKeyFrames;
else
2022-03-28 21:20:28 +08:00
return vector<KeyFrame *>(mvpOrderedConnectedKeyFrames.begin(), mvpOrderedConnectedKeyFrames.begin() + N);
2020-12-01 11:58:17 +08:00
}
// 得到与该关键帧连接的权重大于等于w的关键帧
2022-03-28 21:20:28 +08:00
vector<KeyFrame *> KeyFrame::GetCovisiblesByWeight(const int &w)
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexConnections);
// 如果没有和当前关键帧连接的关键帧
2022-03-28 21:20:28 +08:00
if (mvpOrderedConnectedKeyFrames.empty())
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
return vector<KeyFrame *>();
2020-12-01 11:58:17 +08:00
}
// 从mvOrderedWeights找出第一个大于w的那个迭代器
2022-03-28 21:20:28 +08:00
vector<int>::iterator it = upper_bound(mvOrderedWeights.begin(), mvOrderedWeights.end(), w, KeyFrame::weightComp);
2020-12-01 11:58:17 +08:00
// 如果没有找到(最大的权重也比给定的阈值小)
2022-03-28 21:20:28 +08:00
if (it == mvOrderedWeights.end() && mvOrderedWeights.back() < w)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
return vector<KeyFrame *>();
2020-12-01 11:58:17 +08:00
}
else
{
2022-03-28 21:20:28 +08:00
int n = it - mvOrderedWeights.begin();
return vector<KeyFrame *>(mvpOrderedConnectedKeyFrames.begin(), mvpOrderedConnectedKeyFrames.begin() + n);
2020-12-01 11:58:17 +08:00
}
}
// 得到该关键帧与pKF的权重
int KeyFrame::GetWeight(KeyFrame *pKF)
{
unique_lock<mutex> lock(mMutexConnections);
2022-03-28 21:20:28 +08:00
// 没有连接的话权重也就是共视点个数就是0
if (mConnectedKeyFrameWeights.count(pKF))
2020-12-01 11:58:17 +08:00
return mConnectedKeyFrameWeights[pKF];
else
return 0;
}
int KeyFrame::GetNumberMPs()
{
unique_lock<mutex> lock(mMutexFeatures);
int numberMPs = 0;
2022-03-28 21:20:28 +08:00
for (size_t i = 0, iend = mvpMapPoints.size(); i < iend; i++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (!mvpMapPoints[i])
2020-12-01 11:58:17 +08:00
continue;
numberMPs++;
}
return numberMPs;
}
void KeyFrame::AddMapPoint(MapPoint *pMP, const size_t &idx)
{
unique_lock<mutex> lock(mMutexFeatures);
2022-03-28 21:20:28 +08:00
mvpMapPoints[idx] = pMP;
2020-12-01 11:58:17 +08:00
}
/**
* @brief ,(bad==true),NULL
*
* @param[in] idx id
*/
void KeyFrame::EraseMapPointMatch(const int &idx)
{
unique_lock<mutex> lock(mMutexFeatures);
2022-03-28 21:20:28 +08:00
mvpMapPoints[idx] = static_cast<MapPoint *>(NULL);
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
void KeyFrame::EraseMapPointMatch(MapPoint *pMP)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
tuple<size_t, size_t> indexes = pMP->GetIndexInKeyFrame(this);
2020-12-01 11:58:17 +08:00
size_t leftIndex = get<0>(indexes), rightIndex = get<1>(indexes);
2022-03-28 21:20:28 +08:00
if (leftIndex != -1)
mvpMapPoints[leftIndex] = static_cast<MapPoint *>(NULL);
if (rightIndex != -1)
mvpMapPoints[rightIndex] = static_cast<MapPoint *>(NULL);
2020-12-01 11:58:17 +08:00
}
// 地图点的替换
2022-03-28 21:20:28 +08:00
void KeyFrame::ReplaceMapPointMatch(const int &idx, MapPoint *pMP)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
mvpMapPoints[idx] = pMP;
2020-12-01 11:58:17 +08:00
}
// 获取当前关键帧中的所有地图点
2022-03-28 21:20:28 +08:00
set<MapPoint *> KeyFrame::GetMapPoints()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexFeatures);
2022-03-28 21:20:28 +08:00
set<MapPoint *> s;
for (size_t i = 0, iend = mvpMapPoints.size(); i < iend; i++)
2020-12-01 11:58:17 +08:00
{
// 判断是否被删除了
2022-03-28 21:20:28 +08:00
if (!mvpMapPoints[i])
2020-12-01 11:58:17 +08:00
continue;
2022-03-28 21:20:28 +08:00
MapPoint *pMP = mvpMapPoints[i];
2020-12-01 11:58:17 +08:00
// 如果是没有来得及删除的坏点也要进行这一步
2022-03-28 21:20:28 +08:00
if (!pMP->isBad())
2020-12-01 11:58:17 +08:00
s.insert(pMP);
}
return s;
}
// 关键帧中大于等于最少观测数目minObs的MapPoints的数量.这些特征点被认为追踪到了
int KeyFrame::TrackedMapPoints(const int &minObs)
{
unique_lock<mutex> lock(mMutexFeatures);
2022-03-28 21:20:28 +08:00
int nPoints = 0;
2020-12-01 11:58:17 +08:00
// 是否检查数目
2022-03-28 21:20:28 +08:00
const bool bCheckObs = minObs > 0;
2020-12-01 11:58:17 +08:00
// N是当前帧中特征点的个数
2022-03-28 21:20:28 +08:00
for (int i = 0; i < N; i++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
MapPoint *pMP = mvpMapPoints[i];
if (pMP)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (!pMP->isBad())
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (bCheckObs)
2020-12-01 11:58:17 +08:00
{
// 满足输入阈值要求的地图点计数加1
2022-03-28 21:20:28 +08:00
if (mvpMapPoints[i]->Observations() >= minObs)
2020-12-01 11:58:17 +08:00
nPoints++;
}
else
nPoints++;
}
}
}
return nPoints;
}
// 获取当前关键帧的具体的地图点
2022-03-28 21:20:28 +08:00
vector<MapPoint *> KeyFrame::GetMapPointMatches()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexFeatures);
return mvpMapPoints;
}
// 获取当前关键帧的具体的某个地图点
2022-03-28 21:20:28 +08:00
MapPoint *KeyFrame::GetMapPoint(const size_t &idx)
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexFeatures);
return mvpMapPoints[idx];
}
/*
*
*
* 1. MapPoint3d
* 3d
* 2.
* 3. 便
* covisibility
*/
void KeyFrame::UpdateConnections(bool upParent)
{
2022-03-28 21:20:28 +08:00
map<KeyFrame *, int> KFcounter;
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
vector<MapPoint *> vpMP;
2020-12-01 11:58:17 +08:00
{
// 获得该关键帧的所有3D点
unique_lock<mutex> lockMPs(mMutexFeatures);
vpMP = mvpMapPoints;
}
2022-03-28 21:20:28 +08:00
// For all map points in keyframe check in which other keyframes are they seen
// Increase counter for those keyframes
2020-12-01 11:58:17 +08:00
// 通过3D点间接统计可以观测到这些3D点的所有关键帧之间的共视程度
// Step 1 统计每一个地图点都有多少关键帧与当前关键帧存在共视关系统计结果放在KFcounter
2022-03-28 21:20:28 +08:00
for (vector<MapPoint *>::iterator vit = vpMP.begin(), vend = vpMP.end(); vit != vend; vit++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
MapPoint *pMP = *vit;
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
if (!pMP)
2020-12-01 11:58:17 +08:00
continue;
2022-03-28 21:20:28 +08:00
if (pMP->isBad())
2020-12-01 11:58:17 +08:00
continue;
// 对于每一个MapPoint点observations记录了可以观测到该MapPoint的所有关键帧
2022-03-28 21:20:28 +08:00
map<KeyFrame *, tuple<int, int>> observations = pMP->GetObservations();
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
for (map<KeyFrame *, tuple<int, int>>::iterator mit = observations.begin(), mend = observations.end(); mit != mend; mit++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (mit->first->mnId == mnId || mit->first->isBad() || mit->first->GetMap() != mpMap)
2020-12-01 11:58:17 +08:00
continue;
2022-03-28 21:20:28 +08:00
// 这里的操作非常精彩!
2020-12-01 11:58:17 +08:00
// map[key] = value当要插入的键存在时会覆盖键对应的原来的值。如果键不存在则添加一组键值对
// mit->first 是地图点看到的关键帧,同一个关键帧看到的地图点会累加到该关键帧计数
// 所以最后KFcounter 第一个参数表示某个关键帧第2个参数表示该关键帧看到了多少当前帧的地图点也就是共视程度
KFcounter[mit->first]++;
}
}
// This should not happen
2022-03-28 21:20:28 +08:00
if (KFcounter.empty())
2020-12-01 11:58:17 +08:00
return;
2022-03-28 21:20:28 +08:00
// 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;
2020-12-01 11:58:17 +08:00
// 至少有15个共视地图点
int th = 15;
// vPairs记录与其它关键帧共视帧数大于th的关键帧
// pair<int,KeyFrame*>将关键帧的权重写在前面,关键帧写在后面方便后面排序
2022-03-28 21:20:28 +08:00
vector<pair<int, KeyFrame *>> vPairs;
2020-12-01 11:58:17 +08:00
vPairs.reserve(KFcounter.size());
2022-03-28 21:20:28 +08:00
if (!upParent)
2020-12-01 11:58:17 +08:00
cout << "UPDATE_CONN: current KF " << mnId << endl;
2022-03-28 21:20:28 +08:00
// Step 2 找到对应权重最大的关键帧(共视程度最高的关键帧)
for (map<KeyFrame *, int>::iterator mit = KFcounter.begin(), mend = KFcounter.end(); mit != mend; mit++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (!upParent)
2020-12-01 11:58:17 +08:00
cout << " UPDATE_CONN: KF " << mit->first->mnId << " ; num matches: " << mit->second << endl;
2022-03-28 21:20:28 +08:00
if (mit->second > nmax)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
nmax = mit->second;
pKFmax = mit->first;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
if (mit->second >= th)
2020-12-01 11:58:17 +08:00
{
// 对应权重需要大于阈值,对这些关键帧建立连接
2022-03-28 21:20:28 +08:00
vPairs.push_back(make_pair(mit->second, mit->first));
2020-12-01 11:58:17 +08:00
// 对方关键帧也要添加这个信息
// 更新KFcounter中该关键帧的mConnectedKeyFrameWeights
// 更新其它KeyFrame的mConnectedKeyFrameWeights更新其它关键帧与当前帧的连接权重
2022-03-28 21:20:28 +08:00
(mit->first)->AddConnection(this, mit->second);
2020-12-01 11:58:17 +08:00
}
}
// Step 3 如果没有连接到关键(超过阈值的权重),则对权重最大的关键帧建立连接
2022-03-28 21:20:28 +08:00
if (vPairs.empty())
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
// 如果每个关键帧与它共视的关键帧的个数都少于th
2020-12-01 11:58:17 +08:00
// 那就只更新与其它关键帧共视程度最高的关键帧的mConnectedKeyFrameWeights
// 这是对之前th这个阈值可能过高的一个补丁
2022-03-28 21:20:28 +08:00
vPairs.push_back(make_pair(nmax, pKFmax));
pKFmax->AddConnection(this, nmax);
2020-12-01 11:58:17 +08:00
}
// Step 4 对共视程度比较高的关键帧对更新连接关系及权重(从大到小)
// vPairs里存的都是相互共视程度比较高的关键帧和共视权重接下来由大到小进行排序
2022-03-28 21:20:28 +08:00
sort(vPairs.begin(), vPairs.end()); // sort函数默认升序排列
2020-12-01 11:58:17 +08:00
// 将排序后的结果分别组织成为两种数据类型
2022-03-28 21:20:28 +08:00
list<KeyFrame *> lKFs;
2020-12-01 11:58:17 +08:00
list<int> lWs;
2022-03-28 21:20:28 +08:00
for (size_t i = 0; i < vPairs.size(); i++)
2020-12-01 11:58:17 +08:00
{
// push_front 后变成了从大到小顺序
lKFs.push_front(vPairs[i].second);
lWs.push_front(vPairs[i].first);
}
{
unique_lock<mutex> lockCon(mMutexConnections);
// 更新当前帧与其它关键帧的连接权重
mConnectedKeyFrameWeights = KFcounter;
2022-03-28 21:20:28 +08:00
mvpOrderedConnectedKeyFrames = vector<KeyFrame *>(lKFs.begin(), lKFs.end());
2020-12-01 11:58:17 +08:00
mvOrderedWeights = vector<int>(lWs.begin(), lWs.end());
2022-03-28 21:20:28 +08:00
// Step 5 更新生成树的连接
if (mbFirstConnection && mnId != mpMap->GetInitKFid())
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
// 初始化该关键帧的父关键帧为共视程度最高的那个关键帧
2020-12-01 11:58:17 +08:00
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);
2022-03-28 21:20:28 +08:00
if (pKF == this)
2020-12-01 11:58:17 +08:00
{
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);
}
2022-03-28 21:20:28 +08:00
// 获取当前关键帧的子关键帧
set<KeyFrame *> KeyFrame::GetChilds()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lockCon(mMutexConnections);
return mspChildrens;
}
2022-03-28 21:20:28 +08:00
// 获取当前关键帧的父关键帧
KeyFrame *KeyFrame::GetParent()
2020-12-01 11:58:17 +08:00
{
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);
2022-03-28 21:20:28 +08:00
mbFirstConnection = bFirst;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
2020-12-01 11:58:17 +08:00
// 给当前关键帧添加回环边,回环边连接了形成闭环关系的关键帧
void KeyFrame::AddLoopEdge(KeyFrame *pKF)
{
unique_lock<mutex> lockCon(mMutexConnections);
mbNotErase = true;
mspLoopEdges.insert(pKF);
}
// 获取和当前关键帧形成闭环关系的关键帧
2022-03-28 21:20:28 +08:00
set<KeyFrame *> KeyFrame::GetLoopEdges()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lockCon(mMutexConnections);
return mspLoopEdges;
}
2022-03-28 21:20:28 +08:00
void KeyFrame::AddMergeEdge(KeyFrame *pKF)
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lockCon(mMutexConnections);
mbNotErase = true;
mspMergeEdges.insert(pKF);
}
2022-03-28 21:20:28 +08:00
set<KeyFrame *> KeyFrame::GetMergeEdges()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lockCon(mMutexConnections);
return mspMergeEdges;
}
2022-03-28 21:20:28 +08:00
2020-12-01 11:58:17 +08:00
// 设置当前关键帧不要在优化的过程中被删除. 由回环检测线程调用
void KeyFrame::SetNotErase()
{
unique_lock<mutex> lock(mMutexConnections);
mbNotErase = true;
}
/**
* @brief ,;线
*
*/
void KeyFrame::SetErase()
{
{
unique_lock<mutex> lock(mMutexConnections);
// 如果当前关键帧和其他的关键帧没有形成回环关系,那么就删吧
2022-03-28 21:20:28 +08:00
if (mspLoopEdges.empty())
2020-12-01 11:58:17 +08:00
{
mbNotErase = false;
}
}
// mbToBeErased删除之前记录的想要删但时机不合适没有删除的帧
2022-03-28 21:20:28 +08:00
if (mbToBeErased)
2020-12-01 11:58:17 +08:00
{
SetBadFlag();
}
}
/**
* @brief
*
*
* mbNotErasesim3
* mbNotErasetruesetbadflagmbTobeErasetrue,
* 线 SetErase()mbToBeErased
*/
void KeyFrame::SetBadFlag()
2022-03-28 21:20:28 +08:00
{
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexConnections);
2022-03-28 21:20:28 +08:00
// 初始关键帧不能删除
if (mnId == mpMap->GetInitKFid())
2020-12-01 11:58:17 +08:00
{
return;
}
2022-03-28 21:20:28 +08:00
else if (mbNotErase)
2020-12-01 11:58:17 +08:00
{
// mbNotErase表示不应该删除于是把mbToBeErased置为true假装已经删除其实没有删除
mbToBeErased = true;
return;
}
}
// Step 2 遍历所有和当前关键帧共视的关键帧,删除他们与当前关键帧的联系
2022-03-28 21:20:28 +08:00
for (map<KeyFrame *, int>::iterator mit = mConnectedKeyFrameWeights.begin(), mend = mConnectedKeyFrameWeights.end(); mit != mend; mit++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
mit->first->EraseConnection(this);
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
2020-12-01 11:58:17 +08:00
// Step 3 遍历每一个当前关键帧的地图点,删除每一个地图点和当前关键帧的联系
2022-03-28 21:20:28 +08:00
for (size_t i = 0; i < mvpMapPoints.size(); i++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (mvpMapPoints[i])
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
mvpMapPoints[i]->EraseObservation(this); // 让与自己有联系的MapPoint删除与自己的联系
2020-12-01 11:58:17 +08:00
}
}
{
unique_lock<mutex> lock(mMutexConnections);
unique_lock<mutex> lock1(mMutexFeatures);
// 清空自己与其它关键帧之间的联系
mConnectedKeyFrameWeights.clear();
mvpOrderedConnectedKeyFrames.clear();
2022-03-28 21:20:28 +08:00
// Update Spanning Tree
2020-12-01 11:58:17 +08:00
// Step 4 更新生成树,主要是处理好父子关键帧,不然会造成整个关键帧维护的图断裂,或者混乱,不能够为后端提供较好的初值
// 子关键帧候选父关键帧
2022-03-28 21:20:28 +08:00
set<KeyFrame *> sParentCandidates;
// 将当前帧的父关键帧放入候选父关键帧
if (mpParent)
2020-12-01 11:58:17 +08:00
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
// 如果这个关键帧有自己的子关键帧,告诉这些子关键帧,它们的父关键帧不行了,赶紧找新的父关键帧
2022-03-28 21:20:28 +08:00
while (!mspChildrens.empty())
2020-12-01 11:58:17 +08:00
{
bool bContinue = false;
int max = -1;
2022-03-28 21:20:28 +08:00
KeyFrame *pC;
KeyFrame *pP;
2020-12-01 11:58:17 +08:00
// Step 4.1 遍历每一个子关键帧,让它们更新它们指向的父关键帧
2022-03-28 21:20:28 +08:00
for (set<KeyFrame *>::iterator sit = mspChildrens.begin(), send = mspChildrens.end(); sit != send; sit++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
KeyFrame *pKF = *sit;
2020-12-01 11:58:17 +08:00
// 跳过无效的子关键帧
2022-03-28 21:20:28 +08:00
if (pKF->isBad())
2020-12-01 11:58:17 +08:00
continue;
// Check if a parent candidate is connected to the keyframe
2022-03-28 21:20:28 +08:00
// Step 4.2 子关键帧遍历每一个与它共视的关键帧
vector<KeyFrame *> vpConnected = pKF->GetVectorCovisibleKeyFrames();
for (size_t i = 0, iend = vpConnected.size(); i < iend; i++)
2020-12-01 11:58:17 +08:00
{
// sParentCandidates 中刚开始存的是“爷爷”
2022-03-28 21:20:28 +08:00
for (set<KeyFrame *>::iterator spcit = sParentCandidates.begin(), spcend = sParentCandidates.end(); spcit != spcend; spcit++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (vpConnected[i]->mnId == (*spcit)->mnId)
2020-12-01 11:58:17 +08:00
{
int w = pKF->GetWeight(vpConnected[i]);
// 寻找并更新权值最大的那个共视关系
2022-03-28 21:20:28 +08:00
if (w > max)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
pC = pKF; // 子关键帧
pP = vpConnected[i]; // 目前和子关键帧具有最大权值的关键帧(将来的父关键帧)
max = w; // 这个最大的权值
bContinue = true; // 说明子节点找到了可以作为其新父关键帧的帧
2020-12-01 11:58:17 +08:00
}
}
}
}
}
// Step 4.4 如果在上面的过程中找到了新的父节点
// 下面代码应该放到遍历子关键帧循环中?
// 回答不需要这里while循环还没退出会使用更新的sParentCandidates
2022-03-28 21:20:28 +08:00
if (bContinue)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
// 因为父节点死了,并且子节点找到了新的父节点,就把它更新为自己的父节点
2020-12-01 11:58:17 +08:00
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
// Step 4.5 如果还有子节点没有找到新的父节点
2022-03-28 21:20:28 +08:00
if (!mspChildrens.empty())
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
for (set<KeyFrame *>::iterator sit = mspChildrens.begin(); sit != mspChildrens.end(); sit++)
2020-12-01 11:58:17 +08:00
{
// 直接把父节点的父节点作为自己的父节点 即对于这些子节点来说,他们的新的父节点其实就是自己的爷爷节点
(*sit)->ChangeParent(mpParent);
}
}
2022-03-28 21:20:28 +08:00
if (mpParent)
{
2020-12-01 11:58:17 +08:00
mpParent->EraseChild(this);
2022-03-28 21:20:28 +08:00
// 如果当前的关键帧要被删除的话就要计算这个,表示原父关键帧到当前关键帧的位姿变换
2020-12-01 11:58:17 +08:00
// 注意在这个删除的过程中,其实并没有将当前关键帧中存储的父关键帧的指针删除掉
2022-03-28 21:20:28 +08:00
mTcp = mTcw * mpParent->GetPoseInverse();
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
// 标记当前关键帧已经死了
2020-12-01 11:58:17 +08:00
mbBad = true;
}
mpMap->EraseKeyFrame(this);
mpKeyFrameDB->erase(this);
}
// 返回当前关键帧是否已经完蛋了
bool KeyFrame::isBad()
{
unique_lock<mutex> lock(mMutexConnections);
return mbBad;
}
// 删除当前关键帧和指定关键帧之间的共视关系
2022-03-28 21:20:28 +08:00
void KeyFrame::EraseConnection(KeyFrame *pKF)
2020-12-01 11:58:17 +08:00
{
// 其实这个应该表示是否真的是有共视关系
bool bUpdate = false;
{
unique_lock<mutex> lock(mMutexConnections);
2022-03-28 21:20:28 +08:00
if (mConnectedKeyFrameWeights.count(pKF))
2020-12-01 11:58:17 +08:00
{
mConnectedKeyFrameWeights.erase(pKF);
2022-03-28 21:20:28 +08:00
bUpdate = true;
2020-12-01 11:58:17 +08:00
}
}
// 如果是真的有共视关系,那么删除之后就要更新共视关系
2022-03-28 21:20:28 +08:00
if (bUpdate)
2020-12-01 11:58:17 +08:00
UpdateBestCovisibles();
}
// 获取某个特征点的邻域中的特征点id,其实这个和 Frame.cc 中的那个函数基本上都是一致的; r为边长半径
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);
2022-03-28 21:20:28 +08:00
// 计算要搜索的cell的范围
2020-12-01 11:58:17 +08:00
float factorX = r;
float factorY = r;
2022-03-28 21:20:28 +08:00
// floor向下取整mfGridElementWidthInv 为每个像素占多少个格子
const int nMinCellX = max(0, (int)floor((x - mnMinX - factorX) * mfGridElementWidthInv));
if (nMinCellX >= mnGridCols)
2020-12-01 11:58:17 +08:00
return vIndices;
// ceil向上取整
2022-03-28 21:20:28 +08:00
const int nMaxCellX = min((int)mnGridCols - 1, (int)ceil((x - mnMinX + factorX) * mfGridElementWidthInv));
if (nMaxCellX < 0)
2020-12-01 11:58:17 +08:00
return vIndices;
2022-03-28 21:20:28 +08:00
const int nMinCellY = max(0, (int)floor((y - mnMinY - factorY) * mfGridElementHeightInv));
if (nMinCellY >= mnGridRows)
2020-12-01 11:58:17 +08:00
return vIndices;
2022-03-28 21:20:28 +08:00
const int nMaxCellY = min((int)mnGridRows - 1, (int)ceil((y - mnMinY + factorY) * mfGridElementHeightInv));
if (nMaxCellY < 0)
2020-12-01 11:58:17 +08:00
return vIndices;
// 遍历每个cell,取出其中每个cell中的点,并且每个点都要计算是否在邻域内
2022-03-28 21:20:28 +08:00
for (int ix = nMinCellX; ix <= nMaxCellX; ix++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
for (int iy = nMinCellY; iy <= nMaxCellY; iy++)
2020-12-01 11:58:17 +08:00
{
const vector<size_t> vCell = (!bRight) ? mGrid[ix][iy] : mGridRight[ix][iy];
2022-03-28 21:20:28 +08:00
for (size_t j = 0, jend = vCell.size(); j < jend; j++)
2020-12-01 11:58:17 +08:00
{
const cv::KeyPoint &kpUn = (NLeft == -1) ? mvKeysUn[vCell[j]]
2022-03-28 21:20:28 +08:00
: (!bRight) ? mvKeys[vCell[j]]
: mvKeysRight[vCell[j]];
const float distx = kpUn.pt.x - x;
const float disty = kpUn.pt.y - y;
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
if (fabs(distx) < r && fabs(disty) < r)
2020-12-01 11:58:17 +08:00
vIndices.push_back(vCell[j]);
}
}
}
return vIndices;
}
// 判断某个点是否在当前关键帧的图像中
bool KeyFrame::IsInImage(const float &x, const float &y) const
{
2022-03-28 21:20:28 +08:00
return (x >= mnMinX && x < mnMaxX && y >= mnMinY && y < mnMaxY);
2020-12-01 11:58:17 +08:00
}
/**
* @brief RGBD
*
2022-03-28 21:20:28 +08:00
* @param[in] i i
* @return Eigen::Vector3f
2020-12-01 11:58:17 +08:00
*/
2022-03-28 21:20:28 +08:00
bool KeyFrame::UnprojectStereo(int i, Eigen::Vector3f &x3D)
2020-12-01 11:58:17 +08:00
{
const float z = mvDepth[i];
2022-03-28 21:20:28 +08:00
if (z > 0)
2020-12-01 11:58:17 +08:00
{
// 由2维图像反投影到相机坐标系
// 双目中mvDepth是在ComputeStereoMatches函数中求取的rgbd中是直接测量的
const float u = mvKeys[i].pt.x;
const float v = mvKeys[i].pt.y;
2022-03-28 21:20:28 +08:00
const float x = (u - cx) * z * invfx;
const float y = (v - cy) * z * invfy;
Eigen::Vector3f x3Dc(x, y, z);
2020-12-01 11:58:17 +08:00
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
x3D = mRwc * x3Dc + mTwc.translation();
return true;
2020-12-01 11:58:17 +08:00
}
else
2022-03-28 21:20:28 +08:00
return false;
2020-12-01 11:58:17 +08:00
}
// Compute Scene Depth (q=2 median). Used in monocular. 评估当前关键帧场景深度q=2表示中值. 只是在单目情况下才会使用
// 其实过程就是对当前关键帧下所有地图点的深度进行从小到大排序,返回距离头部其中1/q处的深度值作为当前场景的平均深度
float KeyFrame::ComputeSceneMedianDepth(const int q)
{
2022-03-28 21:20:28 +08:00
if (N == 0)
return -1.0;
vector<MapPoint *> vpMapPoints;
Eigen::Matrix3f Rcw;
Eigen::Vector3f tcw;
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexFeatures);
unique_lock<mutex> lock2(mMutexPose);
vpMapPoints = mvpMapPoints;
2022-03-28 21:20:28 +08:00
tcw = mTcw.translation();
Rcw = mRcw;
2020-12-01 11:58:17 +08:00
}
vector<float> vDepths;
vDepths.reserve(N);
2022-03-28 21:20:28 +08:00
Eigen::Matrix<float, 1, 3> Rcw2 = Rcw.row(2);
float zcw = tcw(2);
2020-12-01 11:58:17 +08:00
// 遍历每一个地图点,计算并保存其在当前关键帧下的深度
2022-03-28 21:20:28 +08:00
for (int i = 0; i < N; i++)
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
if (mvpMapPoints[i])
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
MapPoint *pMP = mvpMapPoints[i];
Eigen::Vector3f x3Dw = pMP->GetWorldPos();
float z = Rcw2.dot(x3Dw) + zcw; // (R*x3Dw+t)的第三行即z
2020-12-01 11:58:17 +08:00
vDepths.push_back(z);
}
}
2022-03-28 21:20:28 +08:00
sort(vDepths.begin(), vDepths.end());
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
return vDepths[(vDepths.size() - 1) / q];
2020-12-01 11:58:17 +08:00
}
void KeyFrame::SetNewBias(const IMU::Bias &b)
{
unique_lock<mutex> lock(mMutexPose);
mImuBias = b;
2022-03-28 21:20:28 +08:00
if (mpImuPreintegrated)
2020-12-01 11:58:17 +08:00
mpImuPreintegrated->SetNewBias(b);
}
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetGyroBias()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return Eigen::Vector3f(mImuBias.bwx, mImuBias.bwy, mImuBias.bwz);
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetAccBias()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return Eigen::Vector3f(mImuBias.bax, mImuBias.bay, mImuBias.baz);
2020-12-01 11:58:17 +08:00
}
IMU::Bias KeyFrame::GetImuBias()
{
unique_lock<mutex> lock(mMutexPose);
return mImuBias;
}
2022-03-28 21:20:28 +08:00
Map *KeyFrame::GetMap()
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexMap);
return mpMap;
}
2022-03-28 21:20:28 +08:00
void KeyFrame::UpdateMap(Map *pMap)
2020-12-01 11:58:17 +08:00
{
unique_lock<mutex> lock(mMutexMap);
mpMap = pMap;
}
2022-03-28 21:20:28 +08:00
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)
2020-12-01 11:58:17 +08:00
{
// 3D in absolute coordinates
2022-03-28 21:20:28 +08:00
Eigen::Vector3f P = pMP->GetWorldPos();
2020-12-01 11:58:17 +08:00
// 3D in camera coordinates
2022-03-28 21:20:28 +08:00
Eigen::Vector3f Pc = mRcw * P + mTcw.translation();
float &PcX = Pc(0);
float &PcY = Pc(1);
float &PcZ = Pc(2);
2020-12-01 11:58:17 +08:00
// Check positive depth
2022-03-28 21:20:28 +08:00
if (PcZ < 0.0f)
2020-12-01 11:58:17 +08:00
{
cout << "Negative depth: " << PcZ << endl;
return false;
}
// Project in image and check it is not outside
2022-03-28 21:20:28 +08:00
float invz = 1.0f / PcZ;
u = fx * PcX * invz + cx;
v = fy * PcY * invz + cy;
2020-12-01 11:58:17 +08:00
// cout << "c";
2022-03-28 21:20:28 +08:00
if (u < mnMinX || u > mnMaxX)
2020-12-01 11:58:17 +08:00
return false;
2022-03-28 21:20:28 +08:00
if (v < mnMinY || v > mnMaxY)
2020-12-01 11:58:17 +08:00
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;
2022-03-28 21:20:28 +08:00
if (mDistCoef.total() == 5)
2020-12-01 11:58:17 +08:00
{
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;
}
2022-03-28 21:20:28 +08:00
bool KeyFrame::ProjectPointUnDistort(MapPoint *pMP, cv::Point2f &kp, float &u, float &v)
2020-12-01 11:58:17 +08:00
{
// 3D in absolute coordinates
2022-03-28 21:20:28 +08:00
Eigen::Vector3f P = pMP->GetWorldPos();
2020-12-01 11:58:17 +08:00
// 3D in camera coordinates
2022-03-28 21:20:28 +08:00
Eigen::Vector3f Pc = mRcw * P + mTcw.translation();
float &PcX = Pc(0);
float &PcY = Pc(1);
float &PcZ = Pc(2);
2020-12-01 11:58:17 +08:00
// Check positive depth
2022-03-28 21:20:28 +08:00
if (PcZ < 0.0f)
2020-12-01 11:58:17 +08:00
{
cout << "Negative depth: " << PcZ << endl;
return false;
}
// Project in image and check it is not outside
2022-03-28 21:20:28 +08:00
const float invz = 1.0f / PcZ;
u = fx * PcX * invz + cx;
v = fy * PcY * invz + cy;
2020-12-01 11:58:17 +08:00
2022-03-28 21:20:28 +08:00
if (u < mnMinX || u > mnMaxX)
2020-12-01 11:58:17 +08:00
return false;
2022-03-28 21:20:28 +08:00
if (v < mnMinY || v > mnMaxY)
2020-12-01 11:58:17 +08:00
return false;
kp = cv::Point2f(u, v);
return true;
}
2022-03-28 21:20:28 +08:00
Sophus::SE3f KeyFrame::GetRelativePoseTrl()
2020-12-01 11:58:17 +08:00
{
2022-03-28 21:20:28 +08:00
unique_lock<mutex> lock(mMutexPose);
return mTrl;
2020-12-01 11:58:17 +08:00
}
2022-03-28 21:20:28 +08:00
Sophus::SE3f KeyFrame::GetRelativePoseTlr()
2020-12-01 11:58:17 +08:00
{
2021-08-09 19:34:51 +08:00
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTlr;
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
Sophus::SE3<float> KeyFrame::GetRightPose()
{
2021-08-09 19:34:51 +08:00
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTrl * mTcw;
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
Sophus::SE3<float> KeyFrame::GetRightPoseInverse()
{
2021-08-09 19:34:51 +08:00
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return mTwc * mTlr;
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetRightCameraCenter()
{
2021-08-09 19:34:51 +08:00
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return (mTwc * mTlr).translation();
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Matrix<float, 3, 3> KeyFrame::GetRightRotation()
{
2021-08-09 19:34:51 +08:00
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return (mTrl.so3() * mTcw.so3()).matrix();
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
Eigen::Vector3f KeyFrame::GetRightTranslation()
{
2021-08-09 19:34:51 +08:00
unique_lock<mutex> lock(mMutexPose);
2022-03-28 21:20:28 +08:00
return (mTrl * mTcw).translation();
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
void KeyFrame::SetORBVocabulary(ORBVocabulary *pORBVoc)
{
mpORBvocabulary = pORBVoc;
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
void KeyFrame::SetKeyFrameDatabase(KeyFrameDatabase *pKFDB)
2021-08-09 19:34:51 +08:00
{
2022-03-28 21:20:28 +08:00
mpKeyFrameDB = pKFDB;
2021-08-09 19:34:51 +08:00
}
2022-03-28 21:20:28 +08:00
} // namespace ORB_SLAM