33 #include <opencv2/opencv.hpp> 37 #define FRAME_GRID_ROWS 48 38 #define FRAME_GRID_COLS 64 52 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);
55 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);
58 Frame(
const cv::Mat &imGray,
const double &timeStamp,
ORBextractor* extractor,
ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef,
const float &bf,
const float &thDepth);
87 bool PosInGrid(
const cv::KeyPoint &kp,
int &posX,
int &posY);
89 vector<size_t>
GetFeaturesInArea(
const float &
x,
const float &
y,
const float &r,
const int minLevel=-1,
const int maxLevel=-1)
const;
std::vector< MapPoint * > mvpMapPoints
void ComputeImageBounds(const cv::Mat &imLeft)
bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY)
vector< float > mvInvScaleFactors
void ComputeStereoFromRGBD(const cv::Mat &imDepth)
cv::Mat UnprojectStereo(const int &i)
std::vector< bool > mvbOutlier
cv::Mat GetRotationInverse()
void UpdatePoseMatrices()
static float mfGridElementHeightInv
cv::Mat mDescriptorsRight
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::vector< std::size_t > mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]
std::vector< cv::KeyPoint > mvKeysUn
static float mfGridElementWidthInv
DBoW2::FeatureVector mFeatVec
cv::Mat GetCameraCenter()
ORBVocabulary * mpORBvocabulary
std::vector< float > mvuRight
bool isInFrustum(MapPoint *pMP, float viewingCosLimit)
vector< float > mvLevelSigma2
std::vector< float > mvDepth
std::vector< cv::KeyPoint > mvKeysRight
static bool mbInitialComputations
static long unsigned int nNextId
void AssignFeaturesToGrid()
Vector of words to represent images.
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< cv::KeyPoint > mvKeys
vector< float > mvScaleFactors
Vector of nodes with indexes of local features.
void ExtractORB(int flag, const cv::Mat &im)
void ComputeStereoMatches()
vector< float > mvInvLevelSigma2
void UndistortKeyPoints()
void SetPose(cv::Mat Tcw)
ORBextractor * mpORBextractorRight
vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const
ORBextractor * mpORBextractorLeft