56     if(!frame.
mTcw.empty())
   104         fx = K.at<
float>(0,0);
   105         fy = K.at<
float>(1,1);
   106         cx = K.at<
float>(0,2);
   107         cy = K.at<
float>(1,2);
   119 Frame::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)
   158         fx = K.at<
float>(0,0);
   159         fy = K.at<
float>(1,1);
   160         cx = K.at<
float>(0,2);
   161         cy = K.at<
float>(1,2);
   215         fx = K.at<
float>(0,0);
   216         fy = K.at<
float>(1,1);
   217         cx = K.at<
float>(0,2);
   218         cy = K.at<
float>(1,2);
   235             mGrid[i][j].reserve(nReserve);
   239         const cv::KeyPoint &kp = 
mvKeysUn[i];
   241         int nGridPosX, nGridPosY;
   243             mGrid[nGridPosX][nGridPosY].push_back(i);
   263     mRcw = 
mTcw.rowRange(0,3).colRange(0,3);
   278     const float &PcX = Pc.at<
float>(0);
   279     const float &PcY= Pc.at<
float>(1);
   280     const float &PcZ = Pc.at<
float>(2);
   287     const float invz = 1.0f/PcZ;
   288     const float u=
fx*PcX*invz+
cx;
   289     const float v=
fy*PcY*invz+
cy;
   299     const cv::Mat PO = P-
mOw;
   300     const float dist = cv::norm(PO);
   302     if(dist<minDistance || dist>maxDistance)
   308     const float viewCos = PO.dot(Pn)/dist;
   310     if(viewCos<viewingCosLimit)
   314     const int nPredictedLevel = pMP->
PredictScale(dist,
this);
   327 vector<size_t> 
Frame::GetFeaturesInArea(
const float &x, 
const float  &y, 
const float  &r, 
const int minLevel, 
const int maxLevel)
 const   329     vector<size_t> vIndices;
   348     const bool bCheckLevels = (minLevel>0) || (maxLevel>=0);
   350     for(
int ix = nMinCellX; ix<=nMaxCellX; ix++)
   352         for(
int iy = nMinCellY; iy<=nMaxCellY; iy++)
   354             const vector<size_t> vCell = 
mGrid[ix][iy];
   358             for(
size_t j=0, jend=vCell.size(); j<jend; j++)
   360                 const cv::KeyPoint &kpUn = 
mvKeysUn[vCell[j]];
   363                     if(kpUn.octave<minLevel)
   366                         if(kpUn.octave>maxLevel)
   370                 const float distx = kpUn.pt.x-x;
   371                 const float disty = kpUn.pt.y-y;
   373                 if(fabs(distx)<r && fabs(disty)<r)
   374                     vIndices.push_back(vCell[j]);
   413     cv::Mat mat(
N,2,CV_32F);
   414     for(
int i=0; i<
N; i++)
   416         mat.at<
float>(i,0)=
mvKeys[i].pt.x;
   417         mat.at<
float>(i,1)=
mvKeys[i].pt.y;
   427     for(
int i=0; i<
N; i++)
   429         cv::KeyPoint kp = 
mvKeys[i];
   430         kp.pt.x=mat.at<
float>(i,0);
   431         kp.pt.y=mat.at<
float>(i,1);
   440         cv::Mat mat(4,2,CV_32F);
   441         mat.at<
float>(0,0)=0.0; mat.at<
float>(0,1)=0.0;
   442         mat.at<
float>(1,0)=imLeft.cols; mat.at<
float>(1,1)=0.0;
   443         mat.at<
float>(2,0)=0.0; mat.at<
float>(2,1)=imLeft.rows;
   444         mat.at<
float>(3,0)=imLeft.cols; mat.at<
float>(3,1)=imLeft.rows;
   451         mnMinX = 
min(mat.at<
float>(0,0),mat.at<
float>(2,0));
   452         mnMaxX = max(mat.at<
float>(1,0),mat.at<
float>(3,0));
   453         mnMinY = 
min(mat.at<
float>(0,1),mat.at<
float>(1,1));
   454         mnMaxY = max(mat.at<
float>(2,1),mat.at<
float>(3,1));
   476     vector<vector<size_t> > vRowIndices(nRows,vector<size_t>());
   478     for(
int i=0; i<nRows; i++)
   479         vRowIndices[i].reserve(200);
   483     for(
int iR=0; iR<Nr; iR++)
   486         const float &kpY = kp.pt.y;
   488         const int maxr = ceil(kpY+r);
   489         const int minr = floor(kpY-r);
   491         for(
int yi=minr;yi<=maxr;yi++)
   492             vRowIndices[yi].push_back(iR);
   496     const float minZ = 
mb;
   497     const float minD = 0;
   498     const float maxD = 
mbf/minZ;
   501     vector<pair<int, int> > vDistIdx;
   504     for(
int iL=0; iL<
N; iL++)
   506         const cv::KeyPoint &kpL = 
mvKeys[iL];
   507         const int &levelL = kpL.octave;
   508         const float &vL = kpL.pt.y;
   509         const float &uL = kpL.pt.x;
   511         const vector<size_t> &vCandidates = vRowIndices[vL];
   513         if(vCandidates.empty())
   516         const float minU = uL-maxD;
   517         const float maxU = uL-minD;
   528         for(
size_t iC=0; iC<vCandidates.size(); iC++)
   530             const size_t iR = vCandidates[iC];
   533             if(kpR.octave<levelL-1 || kpR.octave>levelL+1)
   536             const float &uR = kpR.pt.x;
   538             if(uR>=minU && uR<=maxU)
   552         if(bestDist<thOrbDist)
   557             const float scaleduL = round(kpL.pt.x*scaleFactor);
   558             const float scaledvL = round(kpL.pt.y*scaleFactor);
   559             const float scaleduR0 = round(uR0*scaleFactor);
   564             IL.convertTo(IL,CV_32F);
   565             IL = IL - IL.at<
float>(w,w) *cv::Mat::ones(IL.rows,IL.cols,CV_32F);
   567             int bestDist = INT_MAX;
   570             vector<float> vDists;
   571             vDists.resize(2*L+1);
   573             const float iniu = scaleduR0+L-w;
   574             const float endu = scaleduR0+L+w+1;
   578             for(
int incR=-L; incR<=+L; incR++)
   581                 IR.convertTo(IR,CV_32F);
   582                 IR = IR - IR.at<
float>(w,w) *cv::Mat::ones(IR.rows,IR.cols,CV_32F);
   584                 float dist = cv::norm(IL,IR,cv::NORM_L1);
   591                 vDists[L+incR] = dist;
   594             if(bestincR==-L || bestincR==L)
   598             const float dist1 = vDists[L+bestincR-1];
   599             const float dist2 = vDists[L+bestincR];
   600             const float dist3 = vDists[L+bestincR+1];
   602             const float deltaR = (dist1-dist3)/(2.0
f*(dist1+dist3-2.0
f*dist2));
   604             if(deltaR<-1 || deltaR>1)
   610             float disparity = (uL-bestuR);
   612             if(disparity>=minD && disparity<maxD)
   619                 mvDepth[iL]=
mbf/disparity;
   621                 vDistIdx.push_back(pair<int,int>(bestDist,iL));
   626     sort(vDistIdx.begin(),vDistIdx.end());
   627     const float median = vDistIdx[vDistIdx.size()/2].first;
   628     const float thDist = 1.5f*1.4f*median;
   630     for(
int i=vDistIdx.size()-1;i>=0;i--)
   632         if(vDistIdx[i].first<thDist)
   637             mvDepth[vDistIdx[i].second]=-1;
   648     for(
int i=0; i<
N; i++)
   650         const cv::KeyPoint &kp = 
mvKeys[i];
   651         const cv::KeyPoint &kpU = 
mvKeysUn[i];
   653         const float &v = kp.pt.y;
   654         const float &u = kp.pt.x;
   656         const float d = imDepth.at<
float>(v,u);
   675         cv::Mat x3Dc = (cv::Mat_<float>(3,1) << x, y, z);
 
float GetMinDistanceInvariance()
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
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
ORBVocabulary * mpORBvocabulary
virtual void transform(const std::vector< TDescriptor > &features, BowVector &v) const 
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
Vector3d deltaR(const Matrix3d &R)
void AssignFeaturesToGrid()
static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b)
static std::vector< cv::Mat > toDescriptorVector(const cv::Mat &Descriptors)
TFSIMD_FORCE_INLINE const tfScalar & x() const 
float GetMaxDistanceInvariance()
std::vector< cv::KeyPoint > mvKeys
vector< float > mvScaleFactors
void ExtractORB(int flag, const cv::Mat &im)
TFSIMD_FORCE_INLINE const tfScalar & z() const 
void ComputeStereoMatches()
TFSIMD_FORCE_INLINE const tfScalar & w() const 
vector< float > mvInvLevelSigma2
void UndistortKeyPoints()
void SetPose(cv::Mat Tcw)
ORBextractor * mpORBextractorRight
int PredictScale(const float ¤tDist, KeyFrame *pKF)
vector< size_t > GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const 
ORBextractor * mpORBextractorLeft