/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2020 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 .
*/
#ifndef KEYFRAME_H
#define KEYFRAME_H
#include "MapPoint.h"
#include "Thirdparty/DBoW2/DBoW2/BowVector.h"
#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h"
#include "ORBVocabulary.h"
#include "ORBextractor.h"
#include "Frame.h"
#include "KeyFrameDatabase.h"
#include "ImuTypes.h"
#include "GeometricCamera.h"
#include
#include
#include
#include
namespace ORB_SLAM3
{
class Map;
class MapPoint;
class Frame;
class KeyFrameDatabase;
class GeometricCamera;
class KeyFrame
{
template
void serializeMatrix(Archive& ar, cv::Mat& mat, const unsigned int version)
{
int cols, rows, type;
bool continuous;
if (Archive::is_saving::value) {
cols = mat.cols; rows = mat.rows; type = mat.type();
continuous = mat.isContinuous();
}
ar & cols & rows & type & continuous;
if (Archive::is_loading::value)
mat.create(rows, cols, type);
if (continuous) {
const unsigned int data_size = rows * cols * mat.elemSize();
ar & boost::serialization::make_array(mat.ptr(), data_size);
} else {
const unsigned int row_size = cols*mat.elemSize();
for (int i = 0; i < rows; i++) {
ar & boost::serialization::make_array(mat.ptr(i), row_size);
}
}
}
template
void serializeMatrix(Archive& ar, const cv::Mat& mat, const unsigned int version)
{
cv::Mat matAux = mat;
serializeMatrix(ar, matAux,version);
if (Archive::is_loading::value)
{
cv::Mat* ptr;
ptr = (cv::Mat*)( &mat );
*ptr = matAux;
}
}
friend class boost::serialization::access;
template
void serializeVectorKeyPoints(Archive& ar, const vector& vKP, const unsigned int version)
{
int NumEl;
if (Archive::is_saving::value) {
NumEl = vKP.size();
}
ar & NumEl;
vector vKPaux = vKP;
if (Archive::is_loading::value)
vKPaux.reserve(NumEl);
for(int i=0; i < NumEl; ++i)
{
cv::KeyPoint KPi;
if (Archive::is_loading::value)
KPi = cv::KeyPoint();
if (Archive::is_saving::value)
KPi = vKPaux[i];
ar & KPi.angle;
ar & KPi.response;
ar & KPi.size;
ar & KPi.pt.x;
ar & KPi.pt.y;
ar & KPi.class_id;
ar & KPi.octave;
if (Archive::is_loading::value)
vKPaux.push_back(KPi);
}
if (Archive::is_loading::value)
{
vector *ptr;
ptr = (vector*)( &vKP );
*ptr = vKPaux;
}
}
template
void serialize(Archive& ar, const unsigned int version)
{
ar & mnId;
ar & const_cast(mnFrameId);
ar & const_cast(mTimeStamp);
// Grid
ar & const_cast(mnGridCols);
ar & const_cast(mnGridRows);
ar & const_cast(mfGridElementWidthInv);
ar & const_cast(mfGridElementHeightInv);
// Variables of tracking
ar & mnTrackReferenceForFrame;
ar & mnFuseTargetForKF;
// Variables of local mapping
ar & mnBALocalForKF;
ar & mnBAFixedForKF;
ar & mnNumberOfOpt;
// Variables used by KeyFrameDatabase
ar & mnLoopQuery;
ar & mnLoopWords;
ar & mLoopScore;
ar & mnRelocQuery;
ar & mnRelocWords;
ar & mRelocScore;
ar & mnMergeQuery;
ar & mnMergeWords;
ar & mMergeScore;
ar & mnPlaceRecognitionQuery;
ar & mnPlaceRecognitionWords;
ar & mPlaceRecognitionScore;
ar & mbCurrentPlaceRecognition;
// Variables of loop closing
serializeMatrix(ar,mTcwGBA,version);
serializeMatrix(ar,mTcwBefGBA,version);
serializeMatrix(ar,mVwbGBA,version);
serializeMatrix(ar,mVwbBefGBA,version);
ar & mBiasGBA;
ar & mnBAGlobalForKF;
// Variables of Merging
serializeMatrix(ar,mTcwMerge,version);
serializeMatrix(ar,mTcwBefMerge,version);
serializeMatrix(ar,mTwcBefMerge,version);
serializeMatrix(ar,mVwbMerge,version);
serializeMatrix(ar,mVwbBefMerge,version);
ar & mBiasMerge;
ar & mnMergeCorrectedForKF;
ar & mnMergeForKF;
ar & mfScaleMerge;
ar & mnBALocalForMerge;
// Scale
ar & mfScale;
// Calibration parameters
ar & const_cast(fx);
ar & const_cast(fy);
ar & const_cast(invfx);
ar & const_cast(invfy);
ar & const_cast(cx);
ar & const_cast(cy);
ar & const_cast(mbf);
ar & const_cast(mb);
ar & const_cast(mThDepth);
serializeMatrix(ar,mDistCoef,version);
// Number of Keypoints
ar & const_cast(N);
// KeyPoints
serializeVectorKeyPoints(ar,mvKeys,version);
serializeVectorKeyPoints(ar,mvKeysUn,version);
ar & const_cast& >(mvuRight);
ar & const_cast& >(mvDepth);
serializeMatrix(ar,mDescriptors,version);
// BOW
ar & mBowVec;
ar & mFeatVec;
// Pose relative to parent
serializeMatrix(ar,mTcp,version);
// Scale
ar & const_cast(mnScaleLevels);
ar & const_cast(mfScaleFactor);
ar & const_cast(mfLogScaleFactor);
ar & const_cast& >(mvScaleFactors);
ar & const_cast& >(mvLevelSigma2);
ar & const_cast& >(mvInvLevelSigma2);
// Image bounds and calibration
ar & const_cast(mnMinX);
ar & const_cast(mnMinY);
ar & const_cast(mnMaxX);
ar & const_cast(mnMaxY);
serializeMatrix(ar,mK,version);
// Pose
serializeMatrix(ar,Tcw,version);
// MapPointsId associated to keypoints
ar & mvBackupMapPointsId;
// Grid
ar & mGrid;
// Connected KeyFrameWeight
ar & mBackupConnectedKeyFrameIdWeights;
// Spanning Tree and Loop Edges
ar & mbFirstConnection;
ar & mBackupParentId;
ar & mvBackupChildrensId;
ar & mvBackupLoopEdgesId;
ar & mvBackupMergeEdgesId;
// Bad flags
ar & mbNotErase;
ar & mbToBeErased;
ar & mbBad;
ar & mHalfBaseline;
// Camera variables
ar & mnBackupIdCamera;
ar & mnBackupIdCamera2;
// Fisheye variables
/*ar & mvLeftToRightMatch;
ar & mvRightToLeftMatch;
ar & NLeft;
ar & NRight;
serializeMatrix(ar, mTlr, version);
//serializeMatrix(ar, mTrl, version);
serializeVectorKeyPoints(ar, mvKeysRight, version);
ar & mGridRight;
// Inertial variables
ar & mImuBias;
ar & mBackupImuPreintegrated;
ar & mImuCalib;
ar & mBackupPrevKFId;
ar & mBackupNextKFId;
ar & bImu;
serializeMatrix(ar, Vw, version);
serializeMatrix(ar, Owb, version);*/
}
public:
KeyFrame();
KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB);
// Pose functions
void SetPose(const cv::Mat &Tcw);
void SetVelocity(const cv::Mat &Vw_);
cv::Mat GetPose();
cv::Mat GetPoseInverse();
cv::Mat GetCameraCenter();
cv::Mat GetImuPosition();
cv::Mat GetImuRotation();
cv::Mat GetImuPose();
cv::Mat GetStereoCenter();
cv::Mat GetRotation();
cv::Mat GetTranslation();
cv::Mat GetVelocity();
// Bag of Words Representation
void ComputeBoW();
// Covisibility graph functions
void AddConnection(KeyFrame* pKF, const int &weight);
void EraseConnection(KeyFrame* pKF);
void UpdateConnections(bool upParent=true);
void UpdateBestCovisibles();
std::set GetConnectedKeyFrames();
std::vector GetVectorCovisibleKeyFrames();
std::vector GetBestCovisibilityKeyFrames(const int &N);
std::vector GetCovisiblesByWeight(const int &w);
int GetWeight(KeyFrame* pKF);
// Spanning tree functions
void AddChild(KeyFrame* pKF);
void EraseChild(KeyFrame* pKF);
void ChangeParent(KeyFrame* pKF);
std::set GetChilds();
KeyFrame* GetParent();
bool hasChild(KeyFrame* pKF);
void SetFirstConnection(bool bFirst);
// Loop Edges
void AddLoopEdge(KeyFrame* pKF);
std::set GetLoopEdges();
// Merge Edges
void AddMergeEdge(KeyFrame* pKF);
set GetMergeEdges();
// MapPoint observation functions
int GetNumberMPs();
void AddMapPoint(MapPoint* pMP, const size_t &idx);
void EraseMapPointMatch(const int &idx);
void EraseMapPointMatch(MapPoint* pMP);
void ReplaceMapPointMatch(const int &idx, MapPoint* pMP);
std::set GetMapPoints();
std::vector GetMapPointMatches();
int TrackedMapPoints(const int &minObs);
MapPoint* GetMapPoint(const size_t &idx);
// KeyPoint functions
std::vector GetFeaturesInArea(const float &x, const float &y, const float &r, const bool bRight = false) const;
cv::Mat UnprojectStereo(int i);
// Image
bool IsInImage(const float &x, const float &y) const;
// Enable/Disable bad flag changes
void SetNotErase();
void SetErase();
// Set/check bad flag
void SetBadFlag();
bool isBad();
// Compute Scene Depth (q=2 median). Used in monocular.
float ComputeSceneMedianDepth(const int q);
static bool weightComp( int a, int b){
return a>b;
}
static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){
return pKF1->mnIdmnId;
}
Map* GetMap();
void UpdateMap(Map* pMap);
void SetNewBias(const IMU::Bias &b);
cv::Mat GetGyroBias();
cv::Mat GetAccBias();
IMU::Bias GetImuBias();
bool ProjectPointDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
bool ProjectPointUnDistort(MapPoint* pMP, cv::Point2f &kp, float &u, float &v);
void PreSave(set& spKF,set& spMP, set& spCam);
void PostLoad(map& mpKFid, map& mpMPid, map& mpCamId);
void SetORBVocabulary(ORBVocabulary* pORBVoc);
void SetKeyFrameDatabase(KeyFrameDatabase* pKFDB);
bool bImu;
// The following variables are accesed from only 1 thread or never change (no mutex needed).
public:
static long unsigned int nNextId;
long unsigned int mnId;
const long unsigned int mnFrameId;
const double mTimeStamp;
// Grid (to speed up feature matching)
const int mnGridCols;
const int mnGridRows;
const float mfGridElementWidthInv;
const float mfGridElementHeightInv;
// Variables used by the tracking
long unsigned int mnTrackReferenceForFrame;
long unsigned int mnFuseTargetForKF;
// Variables used by the local mapping
long unsigned int mnBALocalForKF;
long unsigned int mnBAFixedForKF;
//Number of optimizations by BA(amount of iterations in BA)
long unsigned int mnNumberOfOpt;
// Variables used by the keyframe database
long unsigned int mnLoopQuery;
int mnLoopWords;
float mLoopScore;
long unsigned int mnRelocQuery;
int mnRelocWords;
float mRelocScore;
long unsigned int mnMergeQuery;
int mnMergeWords;
float mMergeScore;
long unsigned int mnPlaceRecognitionQuery;
int mnPlaceRecognitionWords;
float mPlaceRecognitionScore;
bool mbCurrentPlaceRecognition;
// Variables used by loop closing
cv::Mat mTcwGBA;
cv::Mat mTcwBefGBA;
cv::Mat mVwbGBA;
cv::Mat mVwbBefGBA;
IMU::Bias mBiasGBA;
long unsigned int mnBAGlobalForKF;
// Variables used by merging
cv::Mat mTcwMerge;
cv::Mat mTcwBefMerge;
cv::Mat mTwcBefMerge;
cv::Mat mVwbMerge;
cv::Mat mVwbBefMerge;
IMU::Bias mBiasMerge;
long unsigned int mnMergeCorrectedForKF;
long unsigned int mnMergeForKF;
float mfScaleMerge;
long unsigned int mnBALocalForMerge;
float mfScale;
// Calibration parameters
const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth;
cv::Mat mDistCoef;
// Number of KeyPoints
const int N;
// KeyPoints, stereo coordinate and descriptors (all associated by an index)
const std::vector mvKeys;
const std::vector mvKeysUn;
const std::vector mvuRight; // negative value for monocular points
const std::vector mvDepth; // negative value for monocular points
const cv::Mat mDescriptors;
//BoW
DBoW2::BowVector mBowVec;
DBoW2::FeatureVector mFeatVec;
// Pose relative to parent (this is computed when bad flag is activated)
cv::Mat mTcp;
// Scale
const int mnScaleLevels;
const float mfScaleFactor;
const float mfLogScaleFactor;
const std::vector mvScaleFactors;
const std::vector mvLevelSigma2;
const std::vector mvInvLevelSigma2;
// Image bounds and calibration
const int mnMinX;
const int mnMinY;
const int mnMaxX;
const int mnMaxY;
const cv::Mat mK;
// Preintegrated IMU measurements from previous keyframe
KeyFrame* mPrevKF;
KeyFrame* mNextKF;
IMU::Preintegrated* mpImuPreintegrated;
IMU::Calib mImuCalib;
unsigned int mnOriginMapId;
string mNameFile;
int mnDataset;
std::vector mvpLoopCandKFs;
std::vector mvpMergeCandKFs;
bool mbHasHessian;
cv::Mat mHessianPose;
// The following variables need to be accessed trough a mutex to be thread safe.
protected:
// SE3 Pose and camera center
cv::Mat Tcw;
cv::Mat Twc;
cv::Mat Ow;
cv::Mat Cw; // Stereo middel point. Only for visualization
// IMU position
cv::Mat Owb;
// Velocity (Only used for inertial SLAM)
cv::Mat Vw;
// Imu bias
IMU::Bias mImuBias;
// MapPoints associated to keypoints
std::vector mvpMapPoints;
// For save relation without pointer, this is necessary for save/load function
std::vector mvBackupMapPointsId;
// BoW
KeyFrameDatabase* mpKeyFrameDB;
ORBVocabulary* mpORBvocabulary;
// Grid over the image to speed up feature matching
std::vector< std::vector > > mGrid;
std::map mConnectedKeyFrameWeights;
std::vector mvpOrderedConnectedKeyFrames;
std::vector mvOrderedWeights;
// For save relation without pointer, this is necessary for save/load function
std::map mBackupConnectedKeyFrameIdWeights;
// Spanning Tree and Loop Edges
bool mbFirstConnection;
KeyFrame* mpParent;
std::set mspChildrens;
std::set mspLoopEdges;
std::set mspMergeEdges;
// For save relation without pointer, this is necessary for save/load function
long long int mBackupParentId;
std::vector mvBackupChildrensId;
std::vector mvBackupLoopEdgesId;
std::vector mvBackupMergeEdgesId;
// Bad flags
bool mbNotErase;
bool mbToBeErased;
bool mbBad;
float mHalfBaseline; // Only for visualization
Map* mpMap;
std::mutex mMutexPose; // for pose, velocity and biases
std::mutex mMutexConnections;
std::mutex mMutexFeatures;
std::mutex mMutexMap;
// Backup variables for inertial
long long int mBackupPrevKFId;
long long int mBackupNextKFId;
IMU::Preintegrated mBackupImuPreintegrated;
// Backup for Cameras
unsigned int mnBackupIdCamera, mnBackupIdCamera2;
public:
GeometricCamera* mpCamera, *mpCamera2;
//Indexes of stereo observations correspondences
std::vector mvLeftToRightMatch, mvRightToLeftMatch;
//Transformation matrix between cameras in stereo fisheye
cv::Mat mTlr;
cv::Mat mTrl;
//KeyPoints in the right image (for stereo fisheye, coordinates are needed)
const std::vector mvKeysRight;
const int NLeft, NRight;
std::vector< std::vector > > mGridRight;
cv::Mat GetRightPose();
cv::Mat GetRightPoseInverse();
cv::Mat GetRightPoseInverseH();
cv::Mat GetRightCameraCenter();
cv::Mat GetRightRotation();
cv::Mat GetRightTranslation();
cv::Mat imgLeft, imgRight; //TODO Backup??
void PrintPointDistribution(){
int left = 0, right = 0;
int Nlim = (NLeft != -1) ? NLeft : N;
for(int i = 0; i < N; i++){
if(mvpMapPoints[i]){
if(i < Nlim) left++;
else right++;
}
}
cout << "Point distribution in KeyFrame: left-> " << left << " --- right-> " << right << endl;
}
};
} //namespace ORB_SLAM
#endif // KEYFRAME_H