@@ -179,7 +179,7 @@ class Frame
179
179
180
180
/* *
181
181
* 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 .
183
183
* viewingCosLimit is a way of limiting the frustum's scope.
184
184
*/
185
185
// Check if a MapPoint is in the frustum of the camera
@@ -190,7 +190,7 @@ class Frame
190
190
* Calculates the coordinates of the grid's cell, to which a keypoint belongs.
191
191
* Informs the coordinates in the posX and posY arguments passed by reference.
192
192
* Returns true if the point belong to the grid, otherwise false.
193
- * @param kp Undistortioned keypoint.
193
+ * @param kp Undistorted keypoint.
194
194
* @param posX X coordinate of the keypoint's cell.
195
195
* @param posY Y coordinate of the keypoint's cell.
196
196
*
@@ -226,112 +226,301 @@ class Frame
226
226
cv::Mat UnprojectStereo (const int &i);
227
227
228
228
public:
229
+ /* * BOW Vocabulary to classify descriptors.*/
229
230
// 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.*/
230
233
ORBVocabulary* mpORBvocabulary;
231
234
235
+ /* * Extractor used to extract descriptors*/
232
236
// Feature extractor. The right is used only in the stereo case.
233
237
ORBextractor* mpORBextractorLeft, *mpORBextractorRight;
234
238
239
+ /* *
240
+ * Image capture's Timestamp.
241
+ * Only for registry and research purposes, it is not used by the algorithm.
242
+ */
235
243
// Frame timestamp.
236
244
double mTimeStamp ;
237
245
246
+ /* *
247
+ * Intrinsic K Matrix, from the camera.
248
+ * Distortion coefficients mDistCoef, intrinsic parameters fx, fy, cx, cy.
249
+ */
238
250
// Calibration matrix and OpenCV distortion parameters.
239
251
cv::Mat mK ;
252
+
253
+ /* * Intrinsic parametersfx, fy, cx, cy.*/
254
+ /* * Intrinsic parameter.*/
240
255
static float fx;
256
+ /* * Intrinsic parameter.*/
241
257
static float fy;
258
+ /* * Intrinsic parameter.*/
242
259
static float cx;
260
+ /* * Intrinsic parameter.*/
243
261
static float cy;
262
+ /* * Inverse of the intrinsic parameter.*/
244
263
static float invfx;
264
+ /* * Intrinsic parameter.*/
245
265
static float invfy;
266
+
267
+ /* * Distortion coefficients of the camera mDistCoef.*/
246
268
cv::Mat mDistCoef ;
247
269
270
+ /* * Not used in monocular.*/
248
271
// Stereo baseline multiplied by fx.
249
272
float mbf;
250
273
274
+ /* * Not used in monocular.*/
251
275
// Stereo baseline in meters.
252
276
float mb;
253
277
278
+ /* * Not used in monocular.*/
254
279
// Threshold close/far points. Close points are inserted from 1 view.
255
280
// Far points are inserted as in the monocular case from 2 views.
256
281
float mThDepth ;
257
282
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
+ */
258
298
// Number of KeyPoints.
259
299
int N;
260
300
261
301
// Vector of keypoints (original for visualization) and undistorted (actually used by the system).
262
302
// In the stereo case, mvKeysUn is redundant as images must be rectified.
263
303
// 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
+ */
264
309
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
+ */
265
319
std::vector<cv::KeyPoint> mvKeysUn;
266
320
267
321
// Corresponding stereo coordinate and depth for each keypoint.
268
322
// "Monocular" keypoints have a negative value.
269
323
std::vector<float > mvuRight;
324
+
325
+ /* * -1 for monocular. It is passed in the Frame's copy constructor.*/
270
326
std::vector<float > mvDepth;
271
327
272
328
// 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
+ */
273
334
DBoW2::BowVector mBowVec ;
335
+
336
+ /* *
337
+ * "Feature" Vector correspondent to the keypoints.
338
+ */
274
339
DBoW2::FeatureVector mFeatVec ;
275
340
341
+ /* * ORB descriptors in Mat format, as returned by opencv. mDescritorRight is not used, passed in the copy constructor.*/
276
342
// ORB descriptor, each row associated to a keypoint.
277
343
cv::Mat mDescriptors , mDescriptorsRight ;
278
344
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
+ */
279
349
// MapPoints associated to keypoints, NULL pointer if no association.
280
350
std::vector<MapPoint*> mvpMapPoints;
281
351
352
+ /* * Flag that indicates if mvpMapPoints contains associated outliers.*/
282
353
// Flag to identify outlier associations.
283
354
std::vector<bool > mvbOutlier;
284
355
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
+ */
285
360
// Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints.
286
361
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
+ */
287
367
static float mfGridElementHeightInv;
288
368
std::vector<std::size_t > mGrid [FRAME_GRID_COLS][FRAME_GRID_ROWS];
289
369
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
+ */
290
401
// Camera pose.
291
402
cv::Mat mTcw ;
292
403
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
+ */
293
409
// Current and Next Frame id.
294
410
static long unsigned int nNextId;
411
+
412
+ /* * Incremental Id that identifies this frame.*/
295
413
long unsigned int mnId;
296
414
415
+ /* * Reference KeyFrame.*/
297
416
// Reference Keyframe.
298
417
KeyFrame* mpReferenceKF;
299
418
419
+ /* * Amount of levels in the pyramid.*/
300
420
// Scale pyramid info.
301
421
int mnScaleLevels;
422
+
423
+ /* * Scale factor between levels of the pyramid.*/
302
424
float mfScaleFactor;
425
+
426
+ /* * Logarithmic scale factor.*/
303
427
float mfLogScaleFactor;
428
+
429
+ /* * Scale factors for each pyramid level vector.*/
304
430
vector<float > mvScaleFactors;
431
+
432
+ /* * Inverse of mvScaleFactors.*/
305
433
vector<float > mvInvScaleFactors;
434
+
435
+ /* * Square of mvScaleFactos.*/
306
436
vector<float > mvLevelSigma2;
437
+
438
+ /* * Inverse of mvLevelSigma2.*/
307
439
vector<float > mvInvLevelSigma2;
308
440
441
+ /* * Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
309
442
// Undistorted Image Bounds (computed once).
310
443
static float mnMinX;
444
+
445
+ /* * Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
311
446
static float mnMaxX;
447
+
448
+ /* * Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
312
449
static float mnMinY;
450
+
451
+ /* * Undistorted image vertices: mnMinX, mnMinY, mnMaxX, mnMaxY.*/
313
452
static float mnMaxY;
314
453
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
+ */
315
458
static bool mbInitialComputations;
316
459
317
460
318
461
private:
319
462
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
+ */
320
469
// Undistort keypoints given OpenCV distortion parameters.
321
470
// Only for the RGB-D case. Stereo must be already rectified!
322
471
// (called in the constructor).
323
472
void UndistortKeyPoints ();
324
473
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
+ */
325
483
// Computes image bounds for the undistorted image (called in the constructor).
326
484
void ComputeImageBounds (const cv::Mat &imLeft);
327
485
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
+ */
328
492
// Assign keypoints to the grid for speed up feature matching (called in the constructor).
329
493
void AssignFeaturesToGrid ();
330
494
331
495
// 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
+ */
332
501
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
+ */
333
507
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
+ */
334
513
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
+ */
335
524
cv::Mat mOw ; // ==mtwc
336
525
};
337
526
0 commit comments