Public Member Functions | List of all members
ov_core::CamRadtan Class Reference

Radial-tangential / Brown–Conrady model pinhole camera model class. More...

#include <CamRadtan.h>

Inheritance diagram for ov_core::CamRadtan:
Inheritance graph
[legend]

Public Member Functions

 CamRadtan (int width, int height)
 Default constructor. More...
 
void compute_distort_jacobian (const Eigen::Vector2d &uv_norm, Eigen::MatrixXd &H_dz_dzn, Eigen::MatrixXd &H_dz_dzeta) override
 Computes the derivative of raw distorted to normalized coordinate. More...
 
Eigen::Vector2f distort_f (const Eigen::Vector2f &uv_norm) override
 Given a normalized uv coordinate this will distort it to the raw image plane. More...
 
Eigen::Vector2f undistort_f (const Eigen::Vector2f &uv_dist) override
 Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords. More...
 
 ~CamRadtan ()
 
- Public Member Functions inherited from ov_core::CamBase
 CamBase (int width, int height)
 Default constructor. More...
 
cv::Point2f distort_cv (const cv::Point2f &uv_norm)
 Given a normalized uv coordinate this will distort it to the raw image plane. More...
 
Eigen::Vector2d distort_d (const Eigen::Vector2d &uv_norm)
 Given a normalized uv coordinate this will distort it to the raw image plane. More...
 
cv::Vec4d get_D ()
 Gets the camera distortion. More...
 
cv::Matx33d get_K ()
 Gets the camera matrix. More...
 
Eigen::MatrixXd get_value ()
 Gets the complete intrinsic vector. More...
 
int h ()
 Gets the height of the camera images. More...
 
virtual void set_value (const Eigen::MatrixXd &calib)
 This will set and update the camera calibration values. This should be called on startup for each camera and after update! More...
 
cv::Point2f undistort_cv (const cv::Point2f &uv_dist)
 Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords. More...
 
Eigen::Vector2d undistort_d (const Eigen::Vector2d &uv_dist)
 Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords. More...
 
int w ()
 Gets the width of the camera images. More...
 
virtual ~CamBase ()
 

Additional Inherited Members

- Protected Member Functions inherited from ov_core::CamBase
 CamBase ()=default
 
- Protected Attributes inherited from ov_core::CamBase
int _height
 Height of the camera (raw pixels) More...
 
int _width
 Width of the camera (raw pixels) More...
 
cv::Vec4d camera_d_OPENCV
 Camera distortion in OpenCV format. More...
 
cv::Matx33d camera_k_OPENCV
 Camera intrinsics in OpenCV format. More...
 
Eigen::MatrixXd camera_values
 Raw set of camera intrinic values (f_x & f_y & c_x & c_y & k_1 & k_2 & k_3 & k_4) More...
 

Detailed Description

Radial-tangential / Brown–Conrady model pinhole camera model class.

To calibrate camera intrinsics, we need to know how to map our normalized coordinates into the raw pixel coordinates on the image plane. We first employ the radial distortion as in OpenCV model:

\begin{align*} \begin{bmatrix} u \\ v \end{bmatrix}:= \mathbf{z}_k &= \mathbf h_d(\mathbf{z}_{n,k}, ~\boldsymbol\zeta) = \begin{bmatrix} f_x * x + c_x \\ f_y * y + c_y \end{bmatrix}\\[1em] \empty {\rm where}~~ x &= x_n (1 + k_1 r^2 + k_2 r^4) + 2 p_1 x_n y_n + p_2(r^2 + 2 x_n^2) \\\ y &= y_n (1 + k_1 r^2 + k_2 r^4) + p_1 (r^2 + 2 y_n^2) + 2 p_2 x_n y_n \\[1em] r^2 &= x_n^2 + y_n^2 \end{align*}

where $ \mathbf{z}_{n,k} = [ x_n ~ y_n ]^\top$ are the normalized coordinates of the 3D feature and u and v are the distorted image coordinates on the image plane. The following distortion and camera intrinsic (focal length and image center) parameters are involved in the above distortion model, which can be estimated online:

\begin{align*} \boldsymbol\zeta = \begin{bmatrix} f_x & f_y & c_x & c_y & k_1 & k_2 & p_1 & p_2 \end{bmatrix}^\top \end{align*}

Note that we do not estimate the higher order (i.e., higher than fourth order) terms as in most offline calibration methods such as Kalibr. To estimate these intrinsic parameters (including the distortation parameters), the following Jacobian for these parameters is needed:

\begin{align*} \frac{\partial \mathbf h_d(\cdot)}{\partial \boldsymbol\zeta} = \begin{bmatrix} x & 0 & 1 & 0 & f_x*(x_nr^2) & f_x*(x_nr^4) & f_x*(2x_ny_n) & f_x*(r^2+2x_n^2) \\[5pt] 0 & y & 0 & 1 & f_y*(y_nr^2) & f_y*(y_nr^4) & f_y*(r^2+2y_n^2) & f_y*(2x_ny_n) \end{bmatrix} \end{align*}

Similarly, the Jacobian with respect to the normalized coordinates can be obtained as follows:

\begin{align*} \frac{\partial \mathbf h_d (\cdot)}{\partial \mathbf{z}_{n,k}} = \begin{bmatrix} f_x*((1+k_1r^2+k_2r^4)+(2k_1x_n^2+4k_2x_n^2(x_n^2+y_n^2))+2p_1y_n+(2p_2x_n+4p_2x_n)) & f_x*(2k_1x_ny_n+4k_2x_ny_n(x_n^2+y_n^2)+2p_1x_n+2p_2y_n) \\ f_y*(2k_1x_ny_n+4k_2x_ny_n(x_n^2+y_n^2)+2p_1x_n+2p_2y_n) & f_y*((1+k_1r^2+k_2r^4)+(2k_1y_n^2+4k_2y_n^2(x_n^2+y_n^2))+(2p_1y_n+4p_1y_n)+2p_2x_n) \end{bmatrix} \end{align*}

To equate this camera class to Kalibr's models, this is what you would use for pinhole-radtan.

Definition at line 82 of file CamRadtan.h.

Constructor & Destructor Documentation

◆ CamRadtan()

ov_core::CamRadtan::CamRadtan ( int  width,
int  height 
)
inline

Default constructor.

Parameters
widthWidth of the camera (raw pixels)
heightHeight of the camera (raw pixels)

Definition at line 90 of file CamRadtan.h.

◆ ~CamRadtan()

ov_core::CamRadtan::~CamRadtan ( )
inline

Definition at line 92 of file CamRadtan.h.

Member Function Documentation

◆ compute_distort_jacobian()

void ov_core::CamRadtan::compute_distort_jacobian ( const Eigen::Vector2d &  uv_norm,
Eigen::MatrixXd &  H_dz_dzn,
Eigen::MatrixXd &  H_dz_dzeta 
)
inlineoverridevirtual

Computes the derivative of raw distorted to normalized coordinate.

Parameters
uv_normNormalized coordinates we wish to distort
H_dz_dznDerivative of measurement z in respect to normalized
H_dz_dzetaDerivative of measurement z in respect to intrinic parameters

Implements ov_core::CamBase.

Definition at line 154 of file CamRadtan.h.

◆ distort_f()

Eigen::Vector2f ov_core::CamRadtan::distort_f ( const Eigen::Vector2f &  uv_norm)
inlineoverridevirtual

Given a normalized uv coordinate this will distort it to the raw image plane.

Parameters
uv_normNormalized coordinates we wish to distort
Returns
2d vector of raw uv coordinate

Implements ov_core::CamBase.

Definition at line 127 of file CamRadtan.h.

◆ undistort_f()

Eigen::Vector2f ov_core::CamRadtan::undistort_f ( const Eigen::Vector2f &  uv_dist)
inlineoverridevirtual

Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.

Parameters
uv_distRaw uv coordinate we wish to undistort
Returns
2d vector of normalized coordinates

Implements ov_core::CamBase.

Definition at line 99 of file CamRadtan.h.


The documentation for this class was generated from the following file:


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17