ov_core::CamRadtan class

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.

Base classes

class CamBase
Base pinhole camera model class.

Constructors, destructors, conversion operators

CamRadtan(int width, int height)
Default constructor.

Public functions

auto undistort_f(const Eigen::Vector2f& uv_dist) -> Eigen::Vector2f override
Given a raw uv point, this will undistort it based on the camera matrices into normalized camera coords.
auto distort_f(const Eigen::Vector2f& uv_norm) -> Eigen::Vector2f override
Given a normalized uv coordinate this will distort it to the raw image plane.
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.

Function documentation

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

Default constructor.

Parameters
width Width of the camera (raw pixels)
height Height of the camera (raw pixels)

Eigen::Vector2f ov_core::CamRadtan::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.

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

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

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

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

void ov_core::CamRadtan::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.

Parameters
uv_norm Normalized coordinates we wish to distort
H_dz_dzn Derivative of measurement z in respect to normalized
H_dz_dzeta Derivative of measurement z in respect to intrinic parameters