Skip to content

Commit ea09d0d

Browse files
Finished documenting Frame.h
1 parent b6d0035 commit ea09d0d

File tree

1 file changed

+191
-2
lines changed

1 file changed

+191
-2
lines changed

include/Frame.h

+191-2
Original file line numberDiff line numberDiff line change
@@ -179,7 +179,7 @@ class Frame
179179

180180
/**
181181
* Indicates if a given 3D point belong to the frame's visual subspace (frustum).
182-
* The visual subspace is a quadrilateral based pyramid, which vertices are those in the frame but undistortioned.
182+
* The visual subspace is a quadrilateral based pyramid, which vertices are those in the frame but undistorted.
183183
* viewingCosLimit is a way of limiting the frustum's scope.
184184
*/
185185
// Check if a MapPoint is in the frustum of the camera
@@ -190,7 +190,7 @@ class Frame
190190
* Calculates the coordinates of the grid's cell, to which a keypoint belongs.
191191
* Informs the coordinates in the posX and posY arguments passed by reference.
192192
* Returns true if the point belong to the grid, otherwise false.
193-
* @param kp Undistortioned keypoint.
193+
* @param kp Undistorted keypoint.
194194
* @param posX X coordinate of the keypoint's cell.
195195
* @param posY Y coordinate of the keypoint's cell.
196196
*
@@ -226,112 +226,301 @@ class Frame
226226
cv::Mat UnprojectStereo(const int &i);
227227

228228
public:
229+
/** BOW Vocabulary to classify descriptors.*/
229230
// Vocabulary used for relocalization.
231+
232+
/** Algorithm used to extract descriptors. The framework allows the developer to test different extractors; ORB-SLAM only uses ORBextractor.*/
230233
ORBVocabulary* mpORBvocabulary;
231234

235+
/** Extractor used to extract descriptors*/
232236
// Feature extractor. The right is used only in the stereo case.
233237
ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
234238

239+
/**
240+
* Image capture's Timestamp.
241+
* Only for registry and research purposes, it is not used by the algorithm.
242+
*/
235243
// Frame timestamp.
236244
double mTimeStamp;
237245

246+
/**
247+
* Intrinsic K Matrix, from the camera.
248+
* Distortion coefficients mDistCoef, intrinsic parameters fx, fy, cx, cy.
249+
*/
238250
// Calibration matrix and OpenCV distortion parameters.
239251
cv::Mat mK;
252+
253+
/** Intrinsic parametersfx, fy, cx, cy.*/
254+
/** Intrinsic parameter.*/
240255
static float fx;
256+
/** Intrinsic parameter.*/
241257
static float fy;
258+
/** Intrinsic parameter.*/
242259
static float cx;
260+
/** Intrinsic parameter.*/
243261
static float cy;
262+
/** Inverse of the intrinsic parameter.*/
244263
static float invfx;
264+
/** Intrinsic parameter.*/
245265
static float invfy;
266+
267+
/** Distortion coefficients of the camera mDistCoef.*/
246268
cv::Mat mDistCoef;
247269

270+
/** Not used in monocular.*/
248271
// Stereo baseline multiplied by fx.
249272
float mbf;
250273

274+
/** Not used in monocular.*/
251275
// Stereo baseline in meters.
252276
float mb;
253277

278+
/** Not used in monocular.*/
254279
// Threshold close/far points. Close points are inserted from 1 view.
255280
// Far points are inserted as in the monocular case from 2 views.
256281
float mThDepth;
257282

283+
/**
284+
* Amount of keypoints.
285+
*
286+
* Size of the paired vectors:
287+
* - mvKeys
288+
* - mvKeysUn
289+
* - mDescriptors
290+
* - mBowVec
291+
* - mFeatVec
292+
* - mvpMapPoints
293+
* - mvbOutlier
294+
*
295+
*
296+
* All these are passed to the keyframe.
297+
*/
258298
// Number of KeyPoints.
259299
int N;
260300

261301
// Vector of keypoints (original for visualization) and undistorted (actually used by the system).
262302
// In the stereo case, mvKeysUn is redundant as images must be rectified.
263303
// In the RGB-D case, RGB images can be distorted.
304+
/**
305+
* Vector of keypoints obtained by the detector, as returned by opencv.
306+
*
307+
* Its coordinates are expressed in pixels, in the image's reference system.
308+
*/
264309
std::vector<cv::KeyPoint> mvKeys, mvKeysRight;
310+
311+
/**
312+
* Vector of undistorted points, mvKeys corrected according to the distortion coefficients.
313+
*
314+
* This vector is paired with mvKeys, both size N.
315+
*
316+
* Its coordinates are expressed in pixels, in the image's reference system.
317+
* The points are obtained by cv::undistortPoints, reapplying the camera's K matrix.
318+
*/
265319
std::vector<cv::KeyPoint> mvKeysUn;
266320

267321
// Corresponding stereo coordinate and depth for each keypoint.
268322
// "Monocular" keypoints have a negative value.
269323
std::vector<float> mvuRight;
324+
325+
/** -1 for monocular. It is passed in the Frame's copy constructor.*/
270326
std::vector<float> mvDepth;
271327

272328
// Bag of Words Vector structures.
329+
/**
330+
* BoW vector correspondent to the keypoints.
331+
*
332+
* BowVector is a Word Id(unsigned int) -> Word value (double) map, which represents a weight.
333+
*/
273334
DBoW2::BowVector mBowVec;
335+
336+
/**
337+
* "Feature" Vector correspondent to the keypoints.
338+
*/
274339
DBoW2::FeatureVector mFeatVec;
275340

341+
/** ORB descriptors in Mat format, as returned by opencv. mDescritorRight is not used, passed in the copy constructor.*/
276342
// ORB descriptor, each row associated to a keypoint.
277343
cv::Mat mDescriptors, mDescriptorsRight;
278344

345+
/** Map's 3D points Vector, associated to the keypoints.
346+
* This vector has the same length as mvKeys and mvKeysUn.
347+
* Unassociated position are NULL.
348+
*/
279349
// MapPoints associated to keypoints, NULL pointer if no association.
280350
std::vector<MapPoint*> mvpMapPoints;
281351

352+
/** Flag that indicates if mvpMapPoints contains associated outliers.*/
282353
// Flag to identify outlier associations.
283354
std::vector<bool> mvbOutlier;
284355

356+
/** mfGridElementWidthInv is the inverse of the cell's width in pixels.
357+
* The points of the undistorted image are divided in cells using a FRAME_GRID_COLS by FRAME_GRID_ROWS grid,
358+
* to reduce the matching complexity.
359+
*/
285360
// Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints.
286361
static float mfGridElementWidthInv;
362+
363+
/** mfGridElementHeightInv is the inverse of the cell's height in pixels .
364+
* The points of the undistorted image are divided in cells using a FRAME_GRID_COLS by FRAME_GRID_ROWS grid,
365+
* to reduce the matching complexity.
366+
*/
287367
static float mfGridElementHeightInv;
288368
std::vector<std::size_t> mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS];
289369

370+
/**
371+
* Camera pose.
372+
* 4x4 rototranslation matrix in homogeneous coordinates.
373+
* It is cv:Mat(4,4,CV_32F), and its elements are type float.
374+
*
375+
* The camera position(translation vector) is obtained from the last column of this matrix.
376+
*
377+
* The unit of measure is established in the initialization according to the scene's average depth.
378+
* This means that the unit depends on the triangulated 3D points in the initialization.
379+
*
380+
* The 3D coordinate system of a camera is related to its projection 2D
381+
* keeping the X and Y axis in parallel, and establishing Z forward.
382+
* In this way X points to the right and Y points downwards (contrary to the standard coordinate system).
383+
* This coordinate system is known as _optical: http://www.ros.org/reps/rep-0103.html#axis-orientation
384+
* The homogeneous 3D vectors have the traditional disposition:
385+
*
386+
* V = [vx, vy, vz, 1]t
387+
*
388+
* The poses are 4x4 matrices as this one, its subindeces indicate reference and subject. Tcw is T in respect to the camera, the world.
389+
* The poses are combined in this way:
390+
*
391+
* Tca = Tba * Tcb
392+
*
393+
* Its value is updated through SetPose, which also extracts the rotation matrix and the translation vector with UpdatePoseMatrices.
394+
* These extracted data is calculated for presentation, but they are not used by the algorithm, that are only used by mTcw.
395+
*
396+
* Frame does not calculate mTcw. This matrix is calculated and passed to the frame using SetPose, in:
397+
* - Tracking, copying a previous frame, initializing the cartesian pose, or estimating through the movement model.
398+
* - Optimizer::PoseOptimization, invoked from multiple Tracking methods. This is where the real pose calculation is made.
399+
*
400+
*/
290401
// Camera pose.
291402
cv::Mat mTcw;
292403

404+
/** Incremental Id with the value for the next frame.
405+
* Its a class variable that keeps record of the id number.
406+
* A frame's id is assigned through
407+
* mnId=nNextId++;
408+
*/
293409
// Current and Next Frame id.
294410
static long unsigned int nNextId;
411+
412+
/** Incremental Id that identifies this frame.*/
295413
long unsigned int mnId;
296414

415+
/** Reference KeyFrame.*/
297416
// Reference Keyframe.
298417
KeyFrame* mpReferenceKF;
299418

419+
/** Amount of levels in the pyramid.*/
300420
// Scale pyramid info.
301421
int mnScaleLevels;
422+
423+
/** Scale factor between levels of the pyramid.*/
302424
float mfScaleFactor;
425+
426+
/** Logarithmic scale factor.*/
303427
float mfLogScaleFactor;
428+
429+
/** Scale factors for each pyramid level vector.*/
304430
vector<float> mvScaleFactors;
431+
432+
/** Inverse of mvScaleFactors.*/
305433
vector<float> mvInvScaleFactors;
434+
435+
/** Square of mvScaleFactos.*/
306436
vector<float> mvLevelSigma2;
437+
438+
/** Inverse of mvLevelSigma2.*/
307439
vector<float> mvInvLevelSigma2;
308440

441+
/** Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
309442
// Undistorted Image Bounds (computed once).
310443
static float mnMinX;
444+
445+
/** Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
311446
static float mnMaxX;
447+
448+
/** Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
312449
static float mnMinY;
450+
451+
/** Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
313452
static float mnMaxY;
314453

454+
/**
455+
* This variable is set to one with a constructor argument only when the first frame is created.
456+
* true for class variable calculations, that are not changed afterwards.
457+
*/
315458
static bool mbInitialComputations;
316459

317460

318461
private:
319462

463+
/**
464+
* Calculates the keypoints of mvKeysUn.
465+
*
466+
* Undistorts detected points, from mvKeys, and saves them in mvKeysUn in the same order.
467+
* If there is no distortion, UndistortKeyPoints quickly returns unifying mvKeysUn = mvKeys in the same vector.
468+
*/
320469
// Undistort keypoints given OpenCV distortion parameters.
321470
// Only for the RGB-D case. Stereo must be already rectified!
322471
// (called in the constructor).
323472
void UndistortKeyPoints();
324473

474+
/**
475+
* Calculates the vertices of the undistorted frame.
476+
* Define mnMinX, mnMaxX, mnMinY, mnMaxY.
477+
* If there is no distortion, the result is trivial with origin at (0,0).
478+
*
479+
* @param imLeft Image, with the only purpose of measuring its size using .rows and .cols .
480+
*
481+
* Only invoked from the constructor.
482+
*/
325483
// Computes image bounds for the undistorted image (called in the constructor).
326484
void ComputeImageBounds(const cv::Mat &imLeft);
327485

486+
/**
487+
* Assigns the keypoints to the corresponding cells in the grid.
488+
* The image is divided in a grid to detect points in a more homogeneous way.
489+
* After undistort the detected keypoints' coordinates,
490+
* this method creates a vector of keypoints for each cell in the grid, and populates it.
491+
*/
328492
// Assign keypoints to the grid for speed up feature matching (called in the constructor).
329493
void AssignFeaturesToGrid();
330494

331495
// Rotation, translation and camera center
496+
497+
/**
498+
* R matrix of rotation of the world respect to the camera.
499+
* It is updated with UpdatePoseMatrices().
500+
*/
332501
cv::Mat mRcw;
502+
503+
/**
504+
* Vector t of translation from the world's origin in the camera's reference system.
505+
* It is updated with UpdatePoseMatrices().
506+
*/
333507
cv::Mat mtcw;
508+
509+
/**
510+
* Inverse of the rotation matrix, de la cámara respecto del mundo.
511+
* It is updated with UpdatePoseMatrices().
512+
*/
334513
cv::Mat mRwc;
514+
515+
/**
516+
* Center of camera vector, camera's position respect to the world.
517+
*
518+
* It is private, informed withFrame::GetCameraCenter.
519+
*
520+
* 3x1 Matrix (vertical vector).
521+
* Inverse translation vector. mtcw is the translation vector of the world's origin in the camera's reference system.
522+
* It is updated with UpdatePoseMatrices().
523+
*/
335524
cv::Mat mOw; //==mtwc
336525
};
337526

0 commit comments

Comments
 (0)