왜곡을 포함한 여러 카메라 모델 탐구하기
이 글은 카메라가 세상을 포착하는 수학적·기하학적 개념을 탐구하며 다양한 카메라 모델의 세부 사항을 깊이 다룬다. 그리고 카메라로 세상의 장면을 이미지로 담을 때, 렌즈의 물리적 특성으로 인해 이미지에 왜곡이 발생한다. 이 왜곡은 컴퓨터 비전 어플리케이션, 3D 복원, 영상 처리 작업의 성능을 크게 저하시킬 수 있다. 이 글은 다섯 가지 카메라 모델을 소개한다. 특히 각 카메라 모델이 왜곡을 이해하고, 보정하는 방법에 대해 자세히 설명한다. 각 모델은 Brown-Conrady, Kannala-Brandt, Scaramuzza, Unified, Double Sphere 모델이며, 그 도식적 표현, 수학적 공식, 파라미터 추정 방법을 탐구한다.
카메라 모델
카메라 모델은 투영(projection)과 역투영(unprojection) 매핑을 정의한다. 투영 매핑은 월드 점을 이미지 평면 위의 이미지 점으로 매핑하고, 역투영 매핑은 이미지 점을 homogeneous 좌표의 월드 점으로 매핑한다. 핀홀 카메라 모델의 경우 여러 매핑 방법들이 있으며 명시적인 왜곡 모델을 가진다. 월드-정규평면 매핑, 왜곡, 정규평면-이미지 매핑. Brown-Conrady 왜곡 모델은 중간에 독립적으로 위치하며 정규화 이미지 평면에서 처리된다. 반면, 예를 들어 Scaramuzza 카메라 모델의 월드-정규화평면 매핑은 투영과 왜곡을 동시에 계산한다. 이 글에서는 왜곡 모델을 포함하는 매핑을 설명하는 데 초점을 맞춘다.
또한 아래 인터랙티브 데모에서 카메라 모델을 선택하고 그 계수를 조절하여 각각의 역할을 확인할 수 있다. 파라미터의 초기값은 위 최적화 방법으로 계산한 캘리브레이션 결과이다.
Brown-Conrady 왜곡 모델
Brown-Conrady 모델은 표준 및 중간 정도의 광각 렌즈에 가장 흔히 사용되는 왜곡 모델 중 하나다. 반경 방향 왜곡(radial distortion)과 접선 방향 왜곡(tangential distortion)을 모두 효과적으로 다룬다.
- 반경 방향 왜곡: 이 왜곡은 직선을, 특히 이미지 가장자리 쪽에서 휘게 하여, 통(barrel) 모양(중심에서 바깥으로 밀려남)이나 바늘꽂이(pincushion) 모양(중심으로 당겨짐)으로 보이게 한다.
- 접선 방향 왜곡: 렌즈면과 이미지 센서면이 평행하게 정렬되지 않을 때 발생하며, 이미지가 약간 기울거나 비틀어지는 결과를 낳는다.
수학적 공식
3D 점 \((X, Y, Z)\)에 대해, 정규화 이미지 좌표에서 왜곡되지 않은 점 \((x, y) = (X/Z, Y/Z)\)과 왜곡된 점 \((x_{d}, y_{d})\)의 관계는 다음과 같이 모델링된다.
\[\begin{align} x_d &= x + x_{\rm rad} + x_{\rm tan}, \\\nonumber y_d &= y+ y_{\rm rad} + y_{\rm tan}, \end{align}\]여기서 반경 방향 왜곡 성분은 다음과 같이 정의된다.
\[\begin{align} x_{\rm rad} &= x (k_1 r^2 + k_2 r^4 + k_3 r^6 + \cdots), \\\nonumber y_{\rm rad} &= y (k_1 r^2 + k_2 r^4 + k_3 r^6 + \cdots), \end{align}\]접선 방향 왜곡 성분은 다음과 같이 정의된다.
\[\begin{align} x_{\rm tan} &= \left(p_1 (r^2 + 2 x^2) + 2 p_2 x y \right) (1 + p_3 r^2 + p_4 r^4 + \cdots), \\\nonumber y_{\rm tan} &= \left(2 p_1 x y + p_2 (r^2 + 2 y^2) \right) (1 + p_3 r^2 + p_4 r^4 + \cdots), \end{align}\]여기서 \(k_1, k_2, k_3, \ldots\)는 반경 방향 왜곡 계수, \(p_1, p_2, \ldots\)는 접선 방향 왜곡 계수, \(r = \sqrt{x^2 + y^2}\)는 이미지 중심으로부터의 거리다. 그러면 이미지 점 \(\mathbf{p} = (u, v)\)는 다음과 같이 주어진다.
\[\begin{align} u &= f_x x_d + c_x, \nonumber\\ v &= f_y y_d + c_y. \end{align}\]Kannala-Brandt 모델
Kannala-Brandt 모델 1은 파라미터 개수에 따라 최대 180도까지의 시야각(FoV)을 갖는 어안(fisheye) 렌즈에 적용할 수 있다. Brown-Conrady 왜곡 모델과 달리, 이 모델은 입사 광선의 각을 픽셀 좌표로 직접 매핑하여 어안 렌즈 특유의 극단적인 비선형 왜곡을 효과적으로 다룬다.
수학적 공식
Kannala-Brandt 모델은 입사각 \(\theta\)를 왜곡된 반경 \(r_d\)로 매핑하기 위해 홀수 차수 다항식을 사용한다.
\[r_d = \theta + k_1 \theta^3 + k_2 \theta^5 + k_3 \theta^7 + k_4 \theta^9 + \cdots,\]여기서 \(k_1, k_2, k_3, k_4, \ldots\)는 왜곡 계수이고, 3D 점 \((X, Y, Z)\)에 대해 \(\theta = \tan^{-1}(\frac{\sqrt{X^2 + Y^2}}{Z})\)는 광축과 입사 광선 사이의 각이다.
그러면 정규화 이미지 좌표에서 왜곡된 점 \((x_d, y_d)\)의 위치는 다음으로 얻는다.
\[\begin{align} x_d &= \frac{r_d}{r} X, \nonumber\\ y_d &= \frac{r_d}{r} Y, \end{align}\]여기서 \(r=\sqrt{X^2 + Y^2}\)는 이미지 중심으로부터 3D 점의 반경 거리다. 그러면 이미지 점 \(\mathbf{p} = (u, v)\)는 다음과 같이 주어진다.
\[\begin{align} u &= f_x x_d + c_x, \nonumber\\ v &= f_y y_d + c_y. \end{align}\]Scaramuzza 모델
Scaramuzza 모델2은 어안 및 반사굴절(catadioptric) 시스템을 포함한 전방향(omnidirectional) 카메라를 다루기 위해 Davide Scaramuzza가 소개했다. 아래에서 설명할 Unified나 Double Sphere 같은 매개변수화된 모델과 달리, 이 모델은 월드 공간에서 이미지 평면으로의 매핑을 다항식으로 기술하여 극단적인 왜곡을 가진 카메라에 더 유연하다.
Scaramuzza 모델은 특정한 광학 설계(예: 단일 시점 투영)를 가정하지 않는다. 대신 테일러 급수 전개를 이용해 카메라의 매핑을 직접 모델링하므로, 반사굴절 및 초광각 어안 렌즈 같은 비단일 시점 카메라에 적합하다.
수학적 공식
카메라 좌표계의 3D 점 \((X, Y, Z)\)에 대해, Scaramuzza 투영 모델은 다음을 이용해 이미지 평면으로 매핑한다.
\[\begin{align} X &= \lambda u, \nonumber\\ Y &= \lambda v, \nonumber\\ Z &= \lambda (a_0 + a_2 \rho^2 + a_3 \rho^3 + a_4 \rho^4), \\ \end{align}\]여기서 \((u, v)\)는 3D 점의 이상적인 이미지 투영, \(\lambda\)는 스칼라 인자, \(a_0, a_2, a_3, a_4\)는 다항식 계수, \(\rho = \sqrt{u^2+v^2}\)는 이미지 중심으로부터의 픽셀 단위 반경 거리다.
3D 점으로부터 투영된 이미지 점을 계산하려면 위 식을 수정해야 한다. \(X, Y\)를 이용하면 \(X^2 + Y^2 = \lambda^2 (u^2 + v^2)\)을 유도할 수 있으므로 다음을 얻는다.
\[\lambda = \frac{\sqrt{X^2+Y^2}}{\rho}.\]위 공식의 \(\lambda\)를 \(Z\)와 \(\rho\)의 관계에 대입하면 다음을 얻는다.
\[f(\rho) = a_0 - \frac{Z}{\sqrt{X^2+Y^2}}\rho + a_2 \rho^2 + a_3 \rho^3 + a_4 \rho^4 = 0.\]주어진 계수 \(a_0, \ldots, a_4\)와 3D 점에 대해, \(f(\rho_r)=0\)이 되는 \(\rho_r\)에 대한 다항식 방정식을 풀 수 있다. 따라서 \((u_c, v_c)\)는 다음과 같이 유도된다.
\[\begin{align} u_c &= \frac{\rho_r}{\sqrt{X^2+Y^2}} X \nonumber\\ v_c &= \frac{\rho_r}{\sqrt{X^2+Y^2}} Y \\ \end{align}\]그러면 왜곡된 점 \((u, v)\)는 다음과 같이 얻는다.
\[\begin{align} \begin{bmatrix} u \\ v \end{bmatrix} = \begin{pmatrix} c & d \\ e & 1 \end{pmatrix} \begin{bmatrix} u_c \\ v_c \end{bmatrix} + \begin{bmatrix} c_x \\ c_y \end{bmatrix}, \end{align}\]여기서 \(c, d, e\)는 행렬의 원소, \((c_x, c_y)\)는 이미지 평면의 왜곡 중심이다. 특수한 경우로, \(d = e = a_2 = a_3 = a_4 = 0\)이면 Scaramuzza 모델은 \(f_x = c a_0, f_y = a_0\)인 핀홀 모델을 설명할 수 있다. 위 다항식 방정식의 근이
\[\rho_r = \frac{\sqrt{X^2+Y^2}}{Z} a_0,\]이고, 이는 다음을 만족하기 때문이다.
\[\begin{align} u &= \frac{c a_0 X}{Z} + c_x, \nonumber\\ v &= \frac{a_0 Y}{Z} + c_y. \end{align}\]Unified 카메라 모델
Unified 카메라 모델3은 Mei 카메라 모델이라고도 하며, 전방향 카메라를 위해 설계되었다. 핀홀 카메라 모델과 구면 투영(spherical projection)을 결합하여 표준 렌즈와 어안 렌즈를 모두 다룰 수 있게 한다. 이 모델은 단일 유효 시점을 활용하여 3D 복원 작업을 단순화한다.

수학적 공식
카메라 프레임의 3D 점 \(\mathbf{P} = (X, Y, Z)\)에 대해, 원점을 중심으로 하는 단위 구로의 투영은 다음과 같다.
\[\overrightarrow{OS} = \frac{1}{\sqrt{X^2+Y^2+Z^2}} (X, Y, Z) := \frac{1}{d} (X, Y, Z),\]여기서 \(d = \sqrt{X^2+Y^2+Z^2}\)는 단위 구 중심으로부터 3D 점까지의 거리다. 이동 파라미터 \(\xi\)로 인해, 대응하는 점은 핀홀 카메라 좌표에서 다음과 같이 표현된다.
\[\overrightarrow{PS} = (\frac{X}{d} , \frac{Y}{d} , \frac{Z}{d} + \xi).\]그러면 정규화 이미지 점 \(\mathbf{x} = [x, y]^T\)는 다음과 같이 주어진다.
\[\begin{align} x &= \frac{X/d}{Z/d + \xi} = \frac{X}{Z + \xi d}, \\ y &= \frac{Y/d}{Z/d + \xi} = \frac{Y}{Z + \xi d}, \\ \end{align}\]여기서 \(\xi\)는 카메라의 유효 시점 이동을 정의하는 모델 파라미터다. 필요하다면 Brown-Conrady 왜곡 모델을 활용하여 왜곡된 이미지 점을 기술할 수 있다.
\[\begin{align} u &= f_x x_d + c_x = f_x (x + x_{\rm rad} + x_{\rm tan}) + c_x, \nonumber\\ v &= f_y y_d + c_y = f_y (y + y_{\rm rad} + y_{\rm tan}) + c_y. \end{align}\]사용하지 않으면, 아래와 같다.
\[\begin{align} u &= f_x x + c_x, \nonumber\\ v &= f_y y + c_y. \end{align}\]Double Sphere 모델
Double Sphere 카메라 모델4은 Unified 카메라 모델의 확장이다. 두 번째 가상 단위 구를 도입하여 극단적인 시야각(180도 이상) 렌즈에 대해 더 나은 정확도를 제공한다. 아래 그림은 Double Sphere 카메라 모델의 도식적 표현이다. 3D 점이 첫 번째와 두 번째 단위 구를 차례로 관통하여 핀홀 카메라 모델의 이미지 평면에 투영된다.

수학적 공식
3D 점 \(\mathbf{X} = (X, Y, Z)\)에 대해, 첫 번째 단위 구로의 투영은
\[\overrightarrow{OS} = \frac{1}{\sqrt{X^2+Y^2+Z^2}}(X, Y, Z) := \frac{1}{d_1} (X,Y,Z),\]이며, 여기서 \(d_1=\sqrt{X^2+Y^2+Z^2}\)는 첫 번째 구 중심으로부터 3D 점까지의의 거리다. 그러면 Unified 카메라 모델과 같은 방식으로, 광선과 두 번째 구의 교점은 다음으로 계산된다.
\[\begin{align} \overrightarrow{QS} &= (\frac{X}{d_1} , \frac{Y}{d_1} , \frac{Z}{d_1} + \xi), \nonumber\\ \overrightarrow{QT} &= \frac{1}{\sqrt{(X/d_1)^2+(Y/d_1)^2+(Z/d_1+\xi)^2}} (\frac{X}{d_1} , \frac{Y}{d_1} , \frac{Z}{d_1} + \xi) \nonumber\\ &= \frac{1}{\sqrt{X^2+Y^2+(Z+\xi d_1)^2}} (X, Y, Z + \xi d_1) \nonumber\\ &:= \frac{1}{d_2} (X, Y, Z + \xi d_1) \nonumber \\ \overrightarrow{PT} &= (\frac{X}{d_2}, \frac{Y}{d_2}, \frac{Z + \xi d_1}{d_2} + \frac{\alpha}{1-\alpha}) \end{align}\]식을 간단히 하기 위해 \(d_2 = \sqrt{X^2+Y^2+(Z+\xi d_1)^2}\)로 정의하였고, 여기서 \(\xi\)는 두 단위 구 사이의 거리를 제어하는 파라미터, \(\alpha\)는 UCM(\(\alpha=0\)일 때)과 Double Sphere 모델 사이의 균형을 결정하는 파라미터다. 따라서 이미지 점 \(\mathbf{p} = [u, v]^T\)는 다음과 같이 주어진다.
\[\begin{align} u &= \frac{f_x (1-\alpha) X}{(1-\alpha)(Z + \xi d_1) + \alpha d_2} + c_x, \\ v &= \frac{f_y (1-\alpha) Y}{(1-\alpha)(Z + \xi d_1) + \alpha d_2} + c_y, \end{align}\]여기서 \(f_x, f_y\)는 초점 거리, \(c_x, c_y\)는 픽셀 단위 주점이다. 필요하다면 Brown-Conrady 왜곡 모델을 활용하여 정확도를 높일 수 있다.
\[\begin{align} u &= f_x d\left(\frac{(1-\alpha) X}{(1-\alpha)(Z + \xi d_1) + \alpha d_2}\right) + c_x, \\ v &= f_y d\left(\frac{(1-\alpha) Y}{(1-\alpha)(Z + \xi d_1) + \alpha d_2}\right) + c_y, \end{align}\]여기서 \(d(\cdot)\)은 Brown-Conrady 왜곡 모델로 점을 왜곡시킨다.
카메라 내부 파라미터 추정
카메라 모델 파라미터를 정확히 추정하는 것은 컴퓨터 비전 시스템의 정밀도를 보장하기 위한 필수 단계다. 이는 일반적으로 Zhang의 방법으로 카메라 캘리브레이션하기에서 언급한 여러 단계를 포함한다.
다양한 카메라 모델을 수용하려면, 최적화 프레임워크 내에서 투영이 적용되는 방식과 파라미터가 파싱되는 방식을 수정해야 한다. 위 글의 MATLAB 코드에서, project와 parse_param 함수가 서로 다른 카메라 모델을 처리하도록 만든다.
다양한 왜곡 모델을 위한 MATLAB 코드 구현
각 모델은 위에서 설명한 수학적 변환을 구현하는 전용 투영 함수를 가진다.
Brown-Conrady 왜곡 모델
function uv = project(xyz, coeffs)
% Implements pinhole camera model and Brown-Conrady distortion model
% coeffs = [fx, fy, s, cx, cy, k1, k2, p1, p2, k3]
coeffs_cell = num2cell(coeffs);
[fx, fy, s, cx, cy, k1, k2, p1, p2, k3] = deal(coeffs_cell{:});
x = xyz(1,:);
y = xyz(2,:);
z = xyz(3,:);
x = x./z;
y = y./z;
r2 = x.^2 + y.^2;
% Radial distortion
radial_factor = 1 + k1*r2 + k2*r2.^2 + k3*r2.^3;
% Tangential distortion
tangential_x = 2*p1*x.*y + p2*(r2 + 2*x.^2);
tangential_y = p1*(r2 + 2*y.^2) + 2*p2*x.*y;
% Apply distortion
x_d = x .* radial_factor + tangential_x;
y_d = y .* radial_factor + tangential_y;
uv = [fx * x_d + cx; fy * y_d + cy];
end
Kannala-Brandt 모델
function uv = project(xyz, coeffs)
% Implements Kannala-Brandt camera model
% coeffs = [fx, fy, s, cx, cy, k1, k2, k3, k4]
coeffs_cell = num2cell(coeffs);
[fx, fy, s, cx, cy, k1, k2, k3, k4] = deal(coeffs_cell{:});
x = xyz(1,:);
y = xyz(2,:);
z = xyz(3,:);
% Calculate incident angle theta and azimuthal angle phi
r = sqrt(x.^2 + y.^2); % Distance in XY plane
theta = atan2(r, z); % Angle from Z-axis
% Apply Kannala-Brandt polynomial to get distorted radius rd
rd = theta + k1*theta.^3 + k2*theta.^5 + k3*theta.^7 + k4*theta.^9;
% Calculate distorted 2D coordinates
xy = [rd .* x ./ r; rd .* y ./ r];
uv = [fx * xy(1,:) + s * xy(2,:) + cx; fy * xy(2,:) + cy];
end
Scaramuzza 모델
function uv = project(xyz, coeffs)
% Implements Scaramuzza (Omnidirectional) distortion model
% coeffs = [c, d, e, cx, cy, a0, a2, a3, a4]
coeffs_cell = num2cell(coeffs);
[c, d, e, cx, cy, a0, a2, a3, a4] = deal(coeffs_cell{:});
x = xyz(1,:);
y = xyz(2,:);
z = xyz(3,:);
rho = zeros(1, length(z));
for i = 1:length(z)
X = x(i);
Y = y(i);
Z = z(i);
r_n = roots([a4, a3, a2, -Z / sqrt(X^2 + Y^2), a0]);
r_n = r_n(imag(r_n) == 0 & r_n > 0);
r_n = real(r_n);
if isempty(r_n)
rho(i) = nan; % to ignore in the optimization loop
else
rho(i) = min(r_n);
end
end
r = sqrt(x.^2 + y.^2);
u = rho .* x ./ r;
v = rho .* y ./ r;
uv = [c*u + d*v + cx; e*u + v + cy];
end
위 함수에서 픽셀 갯수만큼의 for 루프는 계산 성능을 떨어뜨릴 수 있다. 따라서 성능을 높이기 위해, 여러 샘플을 이용해 역다항식 방정식의 계수를 미리 계산한다. sample_ratio가 큰 값일수록 큰 입사각에서 높은 정확도를 보장하지만, 비선형성과 역다항식 방정식의 차수가 증가한다.
function inv_coeffs = find_poly_inv(coeffs, num_sample, sample_ratio, error_thres, max_degree)
% This function finds the inverse form of the given polynomial function.
% This function is used for making the projection computation of Scaramuzza
% model faster.
theta = linspace(0, pi * sample_ratio, num_sample); % num_sample << num_pixel
rho = zeros(1, length(theta));
a0 = coeffs(1);
a2 = coeffs(2);
a3 = coeffs(3);
a4 = coeffs(4);
for i = 1:length(theta)
% theta is an incident angle, theta = atan2(sqrt(X^2+Y^2), Z)
% -Z/sqrt(X^2+Y^2) = -tan(pi/2 - theta)
r_n = roots([a4, a3, a2, -tan(pi/2 - theta(i)), a0]);
r_n = r_n(imag(r_n) == 0 & r_n > 0);
r_n = real(r_n);
if isempty(r_n)
rho(i) = nan;
else
rho(i) = min(r_n);
end
end
error_max = Inf;
degree = 1;
while (error_max > error_thres) && (degree < max_degree)
isValid = ~isnan(rho);
inv_coeffs = polyfit(theta(isValid), rho(isValid), degree);
rho_inv = polyval(inv_coeffs, theta);
error_max = max(abs(rho - rho_inv));
degree = degree + 1;
end
end
function uv = project(xyz, coeffs)
% Implements Scaramuzza (Omnidirectional) distortion model
% coeffs = [c, d, e, cx, cy, a0, a2, a3, a4]
x = xyz(1,:);
y = xyz(2,:);
z = xyz(3,:);
coeffs_cell = num2cell(coeffs);
[c, d, e, cx, cy, a0, a2, a3, a4] = deal(coeffs_cell{:});
inv_coeffs = find_poly_inv([a0, a2, a3, a4], 100, 0.9, 0.01, 25);
r = sqrt(x.^2 + y.^2);
theta = atan2(r, z);
rho = polyval(inv_coeffs, theta);
u = rho .* x ./ r;
v = rho .* y ./ r;
uv = [c*u + d*v + cx; e*u + v + cy];
end
Unified 카메라 모델
function uv = project(xyz, coeffs)
% Implements Unified Camera Model (Mei Model) distortion
% coeffs = [fx, fy, s, cx, cy, xi, k1, k2, p1, p2]
coeffs_cell = num2cell(coeffs);
[fx, fy, s, cx, cy, xi, k1, k2, p1, p2] = = deal(coeffs_cell{:});
x = xyz(1,:);
y = xyz(2,:);
z = xyz(3,:);
% Project to spherical coordinates
d = sqrt(x.^2 + y.^2 + z.^2);
% Apply unified projection
x_p = x ./ (z + xi*d);
y_p = y ./ (z + xi*d);
% Apply radial and tangential distortion (similar to Brown-Conrady)
r2 = x_p.^2 + y_p.^2;
radial_factor = 1 + k1*r2 + k2*r2.^2;
tangential_x = 2*p1*x_p.*y_p + p2*(r2 + 2*x_p.^2);
tangential_y = p1*(r2 + 2*y_p.^2) + 2*p2*x_p.*y_p;
x_d = x_p .* radial_factor + tangential_x;
y_d = y_p .* radial_factor + tangential_y;
uv = [fx * x_d + s * y_d + cx; fy * y_d + cy];
end
Double Sphere 모델
function uv = project(xyz, coeffs)
% Implements Double Sphere distortion model
% coeffs = [fx, fy, s, cx, cy, xi, alpha, k1, k2, p1, p2]
coeffs_cell = num2cell(coeffs);
[fx, fy, s, cx, cy, xi, alpha, k1, k2, p1, p2] = deal(coeffs_cell{:});
x_p = xyz(1,:);
y_p = xyz(2,:);
z_p = xyz(3,:);
% Intermediate calculations
d1 = sqrt(x_p.^2 + y_p.^2 + z_p.^2);
d2 = sqrt(x_p.^2 + y_p.^2 + (z_p + xi*d1).^2);
x = (1-alpha) * x_p ./ ((1-alpha)*(z_p+xi*d1) + alpha*d2);
y = (1-alpha) * y_p ./ ((1-alpha)*(z_p+xi*d1) + alpha*d2);
% Apply radial and tangential distortion (similar to Brown-Conrady)
r2 = x.^2 + y.^2;
radial_factor = 1 + k1*r2 + k2*r2.^2;
tangential_x = 2*p1*x.*y + p2*(r2 + 2*x.^2);
tangential_y = p1*(r2 + 2*y.^2) + 2*p2*x.*y;
x_d = x .* radial_factor + tangential_x;
y_d = y .* radial_factor + tangential_y;
uv = [fx * x_d + s * y_d + cx; fy * y_d + cy];
end
최적화
왜곡 모델에 따라 위 project와 parse_param 함수를 사용하고, Zhang의 방법으로 카메라 캘리브레이션하기의 공통 최적화 알고리즘을 사용하면, 카메라의 내부 및 외부 파라미터를 찾을 수 있다.
정리하며
정확한 이미지 보정과 3D 복원을 달성하려면 적절한 카메라 모델을 이해하고 선택하는 것이 중요하다. 표준 렌즈든 광각 렌즈든 어안 렌즈든, 각 모델은 그에 맞는 강점을 제공한다.
- Brown-Conrady 모델은 표준 응용에 적합하다.
- Kannala-Brandt와 Double Sphere 모델은 넓은 시야각에 적합하다.
- Unified(Mei) 카메라 모델은 약간 넓은 시야각에 적합하다.
- Unified(Mei)와 Double Sphere 카메라 모델은 다항식 방정식이 없어 계산 비용이 저렴하고 명시적으로 닫힌 형태의 역함수(unprojection)를 가진다.
- Scaramuzza 모델은 단일 시점 가정을 따르지 않는 복잡한 카메라 시스템을 위한 비매개변수화 해법을 제공한다.
-
Juho Kannala and Sami S Brandt, A Generic Camera Model and Calibration Method for Conventional, Wide-angle, and Fish-eye Lenses, 2006. ↩
-
Davide Scaramuzza, et. al., A Flexible Technique for Accurate Omnidirectional Camera Calibration and Structure from Motion, 2006. ↩
-
Christopher Mei and Patrick Rives, Single View Point Omnidirectional Camera Calibration from Planar Grids, 2007. ↩
-
Vladyslav Usenko, et. al., The Double Sphere Camera Model, 2018. ↩