Structure containing the intrinsic parameters of a camera. More...
Functions | |
CameraParameters | scale (sl::Resolution const &output_resolution) const |
Return the sl::CameraParameters for another resolution. More... | |
Attributes | |
float | fx |
Focal length in pixels along x axis. More... | |
float | fy |
Focal length in pixels along y axis. More... | |
float | cx |
Optical center along x axis, defined in pixels (usually close to width / 2). More... | |
float | cy |
Optical center along y axis, defined in pixels (usually close to height / 2). More... | |
double | disto [12] |
Distortion factor : [k1, k2, p1, p2, k3, k4, k5, k6, s1, s2, s3, s4]. More... | |
float | v_fov |
Vertical field of view, in degrees. More... | |
float | h_fov |
Horizontal field of view, in degrees. More... | |
float | d_fov |
Diagonal field of view, in degrees. More... | |
Resolution | image_size |
Size in pixels of the images given by the camera. More... | |
float | focal_length_metric |
Real focal length in millimeters. More... | |
Structure containing the intrinsic parameters of a camera.
That information about the camera will be returned by sl::Camera.getCameraInformation().
|
inline |
Return the sl::CameraParameters for another resolution.
output_resolution | : Resolution in which to get the new sl::CameraParameters. |
Referenced by CalibrationParameters::scale().
float fx |
Focal length in pixels along x axis.
Referenced by CameraParameters::scale().
float fy |
Focal length in pixels along y axis.
Referenced by CameraParameters::scale().
float cx |
Optical center along x axis, defined in pixels (usually close to width / 2).
Referenced by CameraParameters::scale().
float cy |
Optical center along y axis, defined in pixels (usually close to height / 2).
Referenced by CameraParameters::scale().
double disto[12] |
Distortion factor : [k1, k2, p1, p2, k3, k4, k5, k6, s1, s2, s3, s4].
Radial (k1, k2, k3, k4, k5, k6), Tangential (p1,p2) and Prism (s1, s2, s3, s4) distortion.
Referenced by CameraParameters::scale().
float v_fov |
Vertical field of view, in degrees.
float h_fov |
Horizontal field of view, in degrees.
float d_fov |
Diagonal field of view, in degrees.
Resolution image_size |
Size in pixels of the images given by the camera.
Referenced by CameraParameters::scale().
float focal_length_metric |
Real focal length in millimeters.