Calibration Class Reference
A Calibration matrix for a finite camera. More...
#include <models/camera/calibration.h>

Public Member Functions | |
| Calibration (const Calibration &cal) | |
| Copy Constructor. | |
| Calibration (const fawkes::Matrix &k) | |
| Constructor. | |
| virtual | ~Calibration () |
| Destructor. | |
| Matrix | K () const |
| Calibration getter. | |
Protected Member Functions | |
| Calibration () | |
| Hidden default constructor. | |
| Calibration & | K (const fawkes::Matrix &k) |
| Sets the calibration matrix. | |
Detailed Description
A Calibration matrix for a finite camera.
Definition at line 30 of file calibration.h.
Constructor & Destructor Documentation
| Calibration::Calibration | ( | const Calibration & | cal | ) |
Copy Constructor.
- Parameters:
-
cal the Calibration to copy
Definition at line 54 of file calibration.cpp.
References K().
| Calibration::Calibration | ( | const fawkes::Matrix & | k | ) |
Constructor.
- Parameters:
-
k 3x3 Calibration matrix of the camera
Definition at line 46 of file calibration.cpp.
References K().
| Calibration::~Calibration | ( | ) | [virtual] |
| Calibration::Calibration | ( | ) | [protected] |
Hidden default constructor.
Definition at line 38 of file calibration.cpp.
References fawkes::Matrix::id().
Member Function Documentation
| Calibration & Calibration::K | ( | const fawkes::Matrix & | k | ) | [protected] |
Sets the calibration matrix.
The matrix k has a size 3x3. The elements (row by row): scale factor in x-direction, skew, x-coordinate of the principal point 0, scale factor in y-direction, y-coordinate of the principal point 0, 0, 1
- Parameters:
-
k the calibration matrix
Definition at line 82 of file calibration.cpp.
References fawkes::Matrix::id(), fawkes::Matrix::overlay(), and fawkes::Matrix::size().
| Matrix Calibration::K | ( | ) | const |
Calibration getter.
- Returns:
- The calibration matrix
Definition at line 69 of file calibration.cpp.
References fawkes::Matrix::get_submatrix().
Referenced by Calibration(), and CCDCalibration::CCDCalibration().
The documentation for this class was generated from the following files:
- src/firevision/models/camera/calibration.h
- src/firevision/models/camera/calibration.cpp

