Class Intrinsics

Class Documentation

class Intrinsics

Implementation of the intrinsic parameterization of cameras.

Apart form the image size, each camera has a projction model, which is represented by a specific calibration matrix \(\mathrm{K}\) and performs the mapping of a 3D scene point (given in the camera coordinate system) to 2D point in the image, as well as a distortion model.

Projection

Most cameras have either a perspective or orthographic (parallel) projection (cf. chapter 6 of (Hartley & Zisserman, 2004)Hartley2004).

Perspective Projection

The perspective projection model (central projection) as described in is the most commonly used projection model for cameras. It is described by a \(3\times 3\) calibration matrix:

\[\begin{split} K = \begin{bmatrix} f_x & \alpha & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 1 \end{bmatrix} , \end{split}\]
with \(f_x\) and \(f_y\) being the focal length, \(c_x\) and \(c_y\) being the coordinates of the principal point and \(\alpha \) being the skew factor.

Orthographic Projection

The orthographic projection model (parallel projection) is described by a \(3\times 3\) calibration matrix:

\[\begin{split} K = \begin{bmatrix} f_x & \alpha & c_x \\ 0 & f_y & c_y \\ 0 & 0 & 0 \end{bmatrix} , \end{split}\]
with \(f_x\) and \(f_y\) being the scaling factor, \(c_x\) and \(c_y\) being the coordinates of the principal point and \(\alpha \) being the skew factor.

Note the difference in the bottom-right place of the matrix. The omission of ‘1’ will result in a loss of depth information when 3D scene points are projected into 2D image points. Thus resulting in a parallel projection.

Distortion

This class supports the distortion models of OpenCV with a maximum of 14 distortion parameters (2 for tangential distortion, 6 for radial distortion, 4 for prism distortion and 2 perspective distortion (Scheimpflug principle).

Public Types

enum EProjectionModel

Enumeration holding possible projection models for the camera intrinsics.

Values:

enumerator PERSPECTIVE

Perspective projection.

enumerator ORTHOGRAPHIC

Orthographic or parallel projection.

Public Functions

inline explicit Intrinsics()

Default constructor, performing a zero initialization.

inline explicit Intrinsics(const cv::Size &iImageSize, const cv::Point2d &iFocalLength, const cv::Point2d &iPrincipalPnt, const cv::Mat &iDistCoeffs = cv::Mat(), const double &iSkew = 0, const EProjectionModel &iProjMod = PERSPECTIVE)

Initialization constructor.

Parameters:
  • iImageSize[in] Initialization of the frame size.

  • iFocalLength[in] Initialization of the focal length.

  • iPrincipalPnt[in] Initialization of the principal point.

  • iDistCoeffs[in] Initialization of the distortion coefficients. See https://docs.opencv.org/master/d9/d0c/group__calib3d.html for more information.

  • iSkew[in] Initialization of skew factor.

  • iProjMod[in] Initialization of projection model.

inline explicit Intrinsics(const int &iWidth, const int &iHeight, const double &iF, const double &iCx, const double &iCy, const cv::Mat &iDistCoeff = cv::Mat(), const double &iSkew = 0, const EProjectionModel &iProjMod = PERSPECTIVE)

Initialization constructor.

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline explicit Intrinsics(const int &iWidth, const int &iHeight, const double &iFx, const double &iFy, const double &iCx, const double &iCy, const cv::Mat &iDistCoeff = cv::Mat(), const double &iSkew = 0, const EProjectionModel &iProjMod = PERSPECTIVE)

Initialization constructor.

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline Intrinsics(const Intrinsics &rhs)

Copy constructor.

inline Intrinsics(Intrinsics &&rhs)

Move constructor.

inline Intrinsics &operator=(const Intrinsics &rhs)

Copy assignment operator.

inline Intrinsics &operator=(Intrinsics &&rhs)

Move assignment operator.

inline EProjectionModel getProjectionModel() const

Returns projection model which is followed by this object.

inline void setProjectionModel(const EProjectionModel &projectionModel)

Method to set projection model which should be represented by the camera, i.e. PERSPECTIVE or ORTHOGRAPHIC.

inline cv::Size getImageSize() const

Returns image size of camera.

inline int getWidth() const

Returns image width of camera.

inline int getHeight() const

Returns image height of camera.

inline void setImageSize(const cv::Size &iImageSize)

Set image size of camera.

inline void setImageSize(const int &iWidth, const int &iHeight)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void setWidth(const int &iWidth)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void setHeight(const int &iHeight)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline cv::Point2d getFocalLength() const

Returns focal length of camera as cv::Point2d.

Note

If the projection model is set to Orhtographic this is interpreted as skaling factor.

inline double getFx() const

Returns focal length in x-direction.

inline double getFy() const

Returns focal length in y-direction.

inline void setFocalLength(const cv::Point2d &iFocalLength)

Method to set focal length of camera.

Parameters:

iFocalLength[in] Focal length. NOTE: If the projection model is set to Orhtographic this is interpreted as skaling factor.

inline void setFocalLength(const double &iFx, const double &iFy)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void setFx(const double &iFx)

Method to set focal length in x-direction.

inline void setFy(const double &iFy)

Method to set focal length in y-direction.

inline cv::Point2d getPrincipalPnt() const

Returns principal point of camera as cv::Point2d.

inline double getCx() const

Returns x-coordinate of principal point.

inline double getCy() const

Returns y-coordinate of principal point.

inline void setPrincipalPnt(const cv::Point2d &iPrincipalPnt)

Method to set principal point of camera.

Parameters:

iPrincipalPnt[in] Coordinates of principal point.

inline void setPrincipalPnt(const double &iCx, const double &iCy)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline void setCx(const double &iCx)

Method to set x-coordinate of principal point.

inline void setCy(const double &iCy)

Method to set y-coordinate of principal point.

inline double getSkew() const

Returns skew factor of camera.

inline void setSkew(double skew)

Method to set skew factor.

inline double getHFov() const

Returns the horizontal field of view (in degrees) computed from focal length and sensor width.

Note

If not all data is avaliable for computation this will return -1.

inline double getVFov() const

Returns the vertical field of view (in degrees) computed from focal length and sensor height.

Note

If not all data is avaliable for computation this will return -1.

inline cv::Matx33d getK_as3x3(const EProjectionModel &iProjectionModel = PERSPECTIVE) const

Method to get the intrinsic parameters as a \(3\times 3\) calibration matrix \(\mathrm{K}\).

Parameters:

iProjectionModel[in] Provide projection model as which \(\mathrm{K}\) is to be returned. Default is PERSPECTIVE. NOTE: This will not change the internal projection model of the object.

inline cv::Matx34d getK_as3x4(const EProjectionModel &iProjectionModel = PERSPECTIVE) const

Method to get the intrinsic parameters as a \(3\times 4\) calibration matrix \(\mathrm{K}\).

In this a zero valued column is appended to \(K\).

Parameters:

iProjectionModel[in] Provide projection model as which \(\mathrm{K}\) is to be returned. Default is PERSPECTIVE. NOTE: This will not change the internal projection model of the object.

inline void setBy_K(const cv::Matx33d &iK)

Method to set the intrinsic parameters by a \(3\times 3\) calibration matrix \(\mathrm{K}\).

Note

If iK(2,2) == 0, this is interpreted as an orthographic calibration matrix and thus mProjectionModel will be updated.

inline void setBy_K(const cv::Matx34d &iK)

Method to set the intrinsic parameters by a \(3\times 4\) calibration matrix \(\mathrm{K}\).

Note

If iK(2,2) == 0 && iK(2,3) == 1, this is interpreted as an orthographic calibration matrix and thus mProjectionModel will be updated.

inline cv::Matx33d getP_as3x3(const EProjectionModel &iProjectionModel = PERSPECTIVE) const

Method to get the projective matrix of the camera as a \(3\times 3\) matrix. In case of a perspective camera this should return an identity matrix.

Parameters:

iProjectionModel[in] Provide projection model as which \(\mathrm{K}\) is to be returned. Default is PERSPECTIVE. NOTE: This will not change the internal projection model of the object.

inline cv::Matx34d getP_as3x4(const EProjectionModel &iProjectionModel = PERSPECTIVE) const

Method to get the projective matrix of the camera as a \(3\times 4\) matrix.

In this a zero valued column is appended to \(P\).

Parameters:

iProjectionModel[in] Provide projection model as which \(\mathrm{K}\) is to be returned. Default is PERSPECTIVE. NOTE: This will not change the internal projection model of the object.

inline cv::Mat getDistortionCoeffs() const

Returns distortion coefficients.

According to the definition of OpenCV this list will hold the fist two radial distortion coefficients ( \(k_1, k_2\)) in the first two places, followd by the two tangential distortion coefficients ( \(p_1, p_2\)), optinally followed by the four remaining radial distortion coefficients ( \(k_3 - k_6\)) and the and the prism distortion coefficients.

inline void setDistortionCoeffs(const cv::Mat &distortionCoeff)

Method to set distortion coefficients.

Parameters:

distortionCoeff[in] According to the definition of OpenCV this list will hold the fist two radial distortion coefficients ( \(k_1, k_2\)) in the first two places, followd by the two tangential distortion coefficients ( \(p_1, p_2\)), optinally followed by the four remaining radial distortion coefficients ( \(k_3 - k_6\)) and the and the prism distortion coefficients.

inline std::vector<double> getRadialDistortionCoeffs() const

Returns the radial distortion coefficients as list of doubles.

inline void setRadialDistortionCoeffs(const std::vector<double> &radialDistCoeffs)

Method to set the radial distortion coefficients as list of doubles.

This will leave the tangential distortion cooefficients unchanged or initialize them to 0.

inline std::vector<double> getTangentialDistortionCoeffs() const

Returns the tangential distortion coefficients as list of doubles.

inline void setTangentialDistortionCoeffs(const std::vector<double> &tangentialDistCoeffs)

Method to set the tangential distortion coefficients as list of doubles.

This will leave the radial distortion cooefficients unchanged or initialize the mandatory ones to 0.

inline std::pair<double, double> undistort(const double &iX, const double &iY) const

Method to undistort a given point.

As described by OpenCV the distortion is considered after the projective devision. Thus the coordinates of the points are to be given with respect to the center of distortion, which typically is the same as the principle point. If not, this class provides a center offset which can be used to shift the center of distortion with respect to the principle point.

Parameters:
  • iX[in] Distorted x-coordinate.

  • iY[in] Distorted y-coordinate.

Returns:

Non-distorted coordinates as std::pair with x at first position.

inline void undistort(const double &iX, const double &iY, double &oX, double &oY) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters:
  • iX[in] Distorted x-coordinate.

  • iY[in] Distorted y-coordinate.

  • oX[out] Non-distorted x-coordinate.

  • oY[out] Non-distorted y-coordinate.

inline cv::Point2d undistort(const cv::Point2d &iImgPnt) const

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

inline std::vector<cv::Point2d> undistort(const std::vector<cv::Point2d> &iImgPnts) const

Method to undistort a given list of image points.

Public Static Functions

static inline void updateIntrinsicFocalLength(Intrinsics intrinsics, double zoom, double minF, double maxF, Intrinsics &outCompensatedIntrinsics)

Method to adapt the intrinsics for the given zoom level.

Parameters:
  • intrinsics[in] Original intrinsics object

  • zoom[in] Zoom level in [0,1]

  • minF[in] Minimum focal length

  • maxF[in] Maximum focal length

  • outCompensatedIntrinsics[out] Adapted intrinsics objects

static inline Intrinsics createIntrinsicsFromFOV(double fov, int width, int height)

Method to create Intrinsics object from field-of-view and image size.

Parameters:
  • fov[in] Field-of-view in degrees, used for vertical and horizontal fov

  • width[in] Image width in pixels

  • height[in] Image height in pixels

Returns:

Created Intrinsics object