/** * This file is part of ORB-SLAM2. * * Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) * For more information see * * ORB-SLAM2 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-SLAM2 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-SLAM2. If not, see . */ #ifndef FRAME_H #define FRAME_H #include #include "MapObject.h" #include "MapPoint.h" #include "Thirdparty/DBoW2/DBoW2/BowVector.h" #include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" #include "ORBVocabulary.h" #include "KeyFrame.h" #include "ORBextractor.h" #include namespace ORB_SLAM2 { #define FRAME_GRID_ROWS 48 #define FRAME_GRID_COLS 64 class MapObject; class MapPoint; class KeyFrame; class Frame { public: Frame(); // Copy constructor. Frame(const Frame &frame); // Constructor for stereo cameras. Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor *extractorLeft, ORBextractor *extractorRight, ORBVocabulary *voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth); // Constructor for RGB-D cameras. Frame(const cv::Mat &imGray, // 灰度化之后的彩色图像 const cv::Mat &imDepth, // 深度图像 const double &timeStamp, // 时间戳 ORBextractor *extractor, // ORB特征提取器句柄 ORBVocabulary *voc, // ORB字典句柄 cv::Mat &K, // 相机的内参数矩阵 cv::Mat &distCoef, // 相机的去畸变参数 const float &bf, // baseline*f const float &thDepth); // 区分远近点的深度阈值) // RGBD构造,添加模板匹配 Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor *extractor, ORBVocabulary *voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth, const vector> &vLabel, cv::Mat &Velocity, bool &state, cv::Mat &Lastframe, float &DepthMapFactor, const cv::Mat &imRGB); // Constructor for Monocular cameras. Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor *extractor, ORBVocabulary *voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth); // Extract ORB on the image. 0 for left image and 1 for right image. void ExtractORB(int flag, const cv::Mat &im); // Compute Bag of Words representation. void ComputeBoW(); // Set the camera pose. void SetPose(cv::Mat Tcw); // Computes rotation, translation and camera center matrices from the camera pose. void UpdatePoseMatrices(); // Returns the camera center. inline cv::Mat GetCameraCenter() { return mOw.clone(); } // Returns inverse of rotation inline cv::Mat GetRotationInverse() { return mRwc.clone(); } // Check if a MapPoint is in the frustum of the camera // and fill variables of the MapPoint to be used by the tracking bool isInFrustum(MapPoint *pMP, float viewingCosLimit); bool isObjInFrustum(MapObject *pMO); // Compute the cell of a keypoint (return false if outside the grid) bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY); vector GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel = -1, const int maxLevel = -1) const; // Search a match for each keypoint in the left image to a keypoint in the right image. // If there is a match, depth is computed and the right coordinate associated to the left keypoint is stored. void ComputeStereoMatches(); // Associate a "right" coordinate to a keypoint if there is valid depth in the depthmap. void ComputeStereoFromRGBD(const cv::Mat &imDepth); // Backprojects a keypoint (if stereo/depth info available) into 3D world coordinates. cv::Mat UnprojectStereo(const int &i); public: // Vocabulary used for relocalization. ORBVocabulary *mpORBvocabulary; // Feature extractor. The right is used only in the stereo case. ORBextractor *mpORBextractorLeft, *mpORBextractorRight; // Frame timestamp. double mTimeStamp; // Calibration matrix and OpenCV distortion parameters. cv::Mat mK; static float fx; static float fy; static float cx; static float cy; static float invfx; static float invfy; cv::Mat mDistCoef; // Stereo baseline multiplied by fx. float mbf; // Stereo baseline in meters. float mb; // Threshold close/far points. Close points are inserted from 1 view. // Far points are inserted as in the monocular case from 2 views. float mThDepth; // Number of KeyPoints. int N; // Vector of keypoints (original for visualization) and undistorted (actually used by the system). // In the stereo case, mvKeysUn is redundant as images must be rectified. // In the RGB-D case, RGB images can be distorted. std::vector mvKeys, mvKeysRight; std::vector mvKeysUn; // Corresponding stereo coordinate and depth for each keypoint. // "Monocular" keypoints have a negative value. std::vector mvuRight; std::vector mvDepth; // Bag of Words Vector structures. DBoW2::BowVector mBowVec; DBoW2::FeatureVector mFeatVec; // ORB descriptor, each row associated to a keypoint. cv::Mat mDescriptors, mDescriptorsRight; // MapPoints associated to keypoints, NULL pointer if no association. std::vector mvpMapPoints; std::vector mvpMapObjects; // Flag to identify outlier associations. std::vector mvbOutlier; std::vector mvbObjOutlier; // Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints. static float mfGridElementWidthInv; static float mfGridElementHeightInv; std::vector mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]; // Camera pose. cv::Mat mTcw; // Current and Next Frame id. static long unsigned int nNextId; long unsigned int mnId; // Reference Keyframe. KeyFrame *mpReferenceKF; // Scale pyramid info. int mnScaleLevels; float mfScaleFactor; float mfLogScaleFactor; vector mvScaleFactors; vector mvInvScaleFactors; vector mvLevelSigma2; vector mvInvLevelSigma2; // Undistorted Image Bounds (computed once). static float mnMinX; static float mnMaxX; static float mnMinY; static float mnMaxY; static bool mbInitialComputations; // 添加动态物体label的vector,及每帧的图像 --by钟 vector> mvvLabel; // cls,x,y,w,h vector> mvvDynamic_label; cv::Mat mGray; // 灰度图 cv::Mat mRGB; cv::Mat mDepth; float mDepthMapFactor; // 用于显示红色动态点 vector vPointRed; // 模板匹配计算相似度 --by钟 static vector mvImg1; static vector mvImD; static cv::Mat mImg2; static vector mvImg1_Tcw; static cv::Mat mImg2_Tcw; private: // Undistort keypoints given OpenCV distortion parameters. // Only for the RGB-D case. Stereo must be already rectified! // (called in the constructor). void UndistortKeyPoints(); // Computes image bounds for the undistorted image (called in the constructor). void ComputeImageBounds(const cv::Mat &imLeft); // Assign keypoints to the grid for speed up feature matching (called in the constructor). void AssignFeaturesToGrid(); // Rotation, translation and camera center cv::Mat mRcw; cv::Mat mtcw; cv::Mat mRwc; cv::Mat mOw; //==mtwc }; } // namespace ORB_SLAM #endif // FRAME_H