Distortion model with parameters.
Terminology:
- principal point \((c_x, c_y)\)
- focal length \((f_x, f_y)\)
- 2x2 diagonal matrix \(\mathrm{diag}(f_x, f_y) = \begin{bmatrix} f_x & 0 \\ 0 & f_y \end{bmatrix}\)
Supported distortion models:
- Pinhole (0 parameters)
- No distortion; equivalent to Brown with \(k_0=k_1=k_2=p_0=p_1=0\).
- Fisheye (4 parameters)
- Also known as equidistant model for pinhole cameras.
- Coefficients \(k_1, k_2, k_3, k_4\) are compatible with ethz-asl/kalibr (pinhole-equi) and OpenCV::fisheye.
- Limitation: this (pinhole + undistort) approach works only for FOV < 180°. TUMVI has ~190°. EuRoC and ORB_SLAM3 use a different approach (direct project/unproject without pinhole) and support > 180°; their coefficients are incompatible with this model.
- Parameters:
- 0..3: \((k_1, k_2, k_3, k_4)\)
- Projection:
- \((u, v) = (c_x, c_y) + \mathrm{diag}(f_x, f_y) \cdot \frac{\mathrm{radial}(r) \cdot (x_n, y_n)}{r}\)
- where:
- \(\mathrm{radial}(r) = \arctan(r) \cdot \left(1 + k_1 \arctan^2(r) + k_2 \arctan^4(r) + k_3 \arctan^6(r) + k_4 \arctan^8(r)\right)\)
- \(x_n = x/z\)
- \(y_n = y/z\)
- \(r = \sqrt{x_n^2 + y_n^2}\)
- Brown (5 parameters)
- Equivalent to Polynomial model with \(k_4=k_5=k_6=0\); note a different order of parameters.
- Parameters:
- 0..2: radial \((k_1, k_2, k_3)\)
- 3..4: tangential \((p_1, p_2)\)
- Projection:
- \((u, v) = (c_x, c_y) + \mathrm{diag}(f_x, f_y) \cdot \left( \mathrm{radial} \cdot (x_n, y_n) + (t_x, t_y) \right)\)
- where:
- \(\mathrm{radial} = 1 + k_1 r^2 + k_2 r^4 + k_3 r^6\)
- \(t_x = 2 p_1 x_n y_n + p_2 (r^2 + 2 x_n^2)\)
- \(t_y = p_1 (r^2 + 2 y_n^2) + 2 p_2 x_n y_n\)
- \(x_n = x/z\)
- \(y_n = y/z\)
- \(r = \sqrt{x_n^2 + y_n^2}\)
- Polynomial (8 parameters)
- Coefficients are compatible with the first 8 coefficients of the OpenCV distortion model.
- Parameters:
- 0..1: radial \((k_1, k_2)\)
- 2..3: tangential \((p_1, p_2)\)
- 4..7: radial \((k_3, k_4, k_5, k_6)\)
- Projection:
- \((u, v) = (c_x, c_y) + \mathrm{diag}(f_x, f_y) \cdot \left( \mathrm{radial} \cdot (x_n, y_n) + (t_x, t_y) \right)\)
- where:
- \(\mathrm{radial} = \frac{1 + k_1 r^2 + k_2 r^4 + k_3 r^6}{1 + k_4 r^2 + k_5 r^4 + k_6 r^6}\)
- \(t_x = 2 p_1 x_n y_n + p_2 (r^2 + 2 x_n^2)\)
- \(t_y = p_1 (r^2 + 2 y_n^2) + 2 p_2 x_n y_n\)
- \(x_n = x/z\)
- \(y_n = y/z\)
- \(r = \sqrt{x_n^2 + y_n^2}\)