Skip to content

Sensor Models

James Yang edited this page Apr 15, 2023 · 33 revisions

Quick links

Camera

Cameras project a point in space resolved in the camera frame into the image space as a pixel with a set of parameters:

$\mathbf{t}^s_{sx}$ is the world point resolved in the camera frame.

$\mathbf{p}$ is pixel location of that point as observed by the camera.

$\boldsymbol{\beta}$ is a vector of intrinsics parameters.

$\mathbf{P}$ is the projection function.

$$\mathbf{p} = \mathbf{P}\left(\mathbf{t}^s_{sx}, \boldsymbol{\beta}\right)$$ $$\mathbf{t}^s_{sx} = \left[\begin{matrix}t_x\\t_y\\t_z\end{matrix}\right]$$

For the derivation of $\mathbf{t}^s_{sx}$, see here.

5-parameter OpenCv Model

Original paper (Brown)

Original paper (Conrady)

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}f&,&c_x&,&c_y&,&k_1&,&k_2&,&p_1&,&p_2&,&k_3\end{matrix}\right]$$

$f$ = focal length

$c_x, c_y$ = image center

$k_1, k_2, k_3$ = Radial distortion parameters

$p_1, p_2$ = Tangential distortion parameters

$$\mathbf{P}\left(\mathbf{t}^s_{sx_i}, \boldsymbol{\beta}\right) = \left[\begin{matrix}f & 0 \\ 0 & f \end{matrix}\right]\mathbf{p}_d + \left[\begin{array}{c}c_x\\c_y\end{array}\right]$$ $$\mathbf{p}_d = s\mathbf{p}_m + \left(2\mathbf{p}_m\mathbf{p}_m^T + r^2\mathbf{I}\right)\left[\begin{array}{c}p_2\\p_1\end{array}\right]$$ $$s = 1 + k_1r^2 + k_2r^4 + k_3r^6$$ $$r^2 = \mathbf{p}_m^T\mathbf{p}_m$$ $$\mathbf{p}_m = \left[\begin{array}{c}t_x / t_z\\ t_y / t_z\end{array}\right]$$

8-parameter OpenCv Model

Original paper (Brown)

Original paper (Conrady)

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}f&,&c_x&,&c_y&,&k_1&,&k_2&,&p_1&,&p_2&,&k_3&,&k_4&,&k_5&,&k_6\end{matrix}\right]$$

$f$ = focal length

$c_x, c_y$ = image center

$k_1, ..., k_6$ = Radial distortion parameters

$p_1, p_2$ = Tangential distortion parameters

$$\mathbf{P}\left(\mathbf{t}^s_{sx_i}, \boldsymbol{\beta}\right) = \left[\begin{matrix}f & 0 \\ 0 & f \end{matrix}\right]\mathbf{p}_d + \left[\begin{array}{c}c_x\\c_y\end{array}\right]$$ $$\mathbf{p}_d = s\mathbf{p}_m + \left(2\mathbf{p}_m\mathbf{p}_m^T + r^2\mathbf{I}\right)\left[\begin{array}{c}p_2\\p_1\end{array}\right]$$ $$s = \frac{1 + k_1r^2 + k_2r^4 + k_3r^6}{1 + k_4r^2 + k_5r^4 + k_6r^6}$$ $$r^2 = \mathbf{p}_m^T\mathbf{p}_m$$ $$\mathbf{p}_m = \left[\begin{array}{c}t_x / t_z\\ t_y / t_z\end{array}\right]$$

Kannala-Brandt Model

Orignal paper

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}f&,&c_x&,&c_y&,&k_1&,&k_2&,&k_3&,&k_4\end{matrix}\right]$$

$f$ = focal length

$c_x, c_y$ = image center

$k_1, k_2, k_3, k_4$ = Radial distortion parameters

$$\mathbf{P}\left(\mathbf{t}^s_{sx_i}, \boldsymbol{\beta}\right) = \left[\begin{matrix}f&0\\0&f\end{matrix}\right]\mathbf{p}_d + \left[\begin{matrix}c_x\\c_y\end{matrix}\right]$$ $$\mathbf{p}_d = \frac{\theta_d}{r}\mathbf{p}_m$$ $$\theta_d = \theta + k_1\theta^3 + k_2\theta^5 + k_3\theta^7 + k_4\theta^9$$ $$\theta = \arctan\left(r\right)$$ $$r^2 = {\mathbf{p}_m}^T\mathbf{p}_m$$ $$\mathbf{p}_m = \left[\begin{matrix}t_x / t_z\\t_y/t_z\end{matrix}\right]$$

Double Sphere Model

Original paper

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}f&,&c_x&,&c_y&,&\xi&,&\alpha\end{matrix}\right]$$

$f$ = focal length

$c_x, c_y$ = image center

$\xi, \alpha$ = distortion parameters

$$\mathbf{P}\left(\mathbf{t}^s_{sx_i}, \boldsymbol{\beta}\right) = \left[\begin{matrix}f&0\\0&f\end{matrix}\right]\mathbf{p}_d + \left[\begin{matrix}c_x\\c_y\end{matrix}\right]$$ $$\mathbf{p}_d = \left(\alpha d + \left(1-\alpha\right) \left(\xi r+t_z\right)\right)^{-1} \left[\begin{matrix}t_x\\t_y\end{matrix}\right]\\$$$$ $$d = \sqrt{r^2\left(1 + \xi^2\right) + 2\xi r t_z}$$ $$r^2 = {\mathbf{t}^s_{sx}}^T\mathbf{t}^s_{sx}$$

Field of View Model

Original paper

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}f&,&c_x&,&c_y&,&w\end{matrix}\right]$$

$f$ = focal length

$c_x, c_y$ = image center

$w$ = distortion parameter

$$\mathbf{P}\left(\mathbf{t}^s_{sx_i}, \boldsymbol{\beta}\right) = \left[\begin{matrix}f&0\\0&f\end{matrix}\right]\mathbf{p}_d + \left[\begin{matrix}c_x\\c_y\end{matrix}\right]$$ $$\mathbf{p}_d = \frac{r_d}{r_u}\mathbf{p}_m$$ $$r_d = \frac{\tan^{-1}\left(2r_u\tan(w/2)\right)}{w}$$ $$r_u = {\mathbf{p}_m}^T\mathbf{p}_m$$ $$\mathbf{p}_m = \left[\begin{matrix}t_x/t_z\\t_y/t_z\end{matrix}\right]$$

Unified Camera Model

Original paper

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}f&,&c_x&,&c_y&,&\alpha\end{matrix}\right]$$

$f$ = focal length

$c_x, c_y$ = image center

$\alpha$ = distortion parameter

$$\mathbf{P}\left(\mathbf{t}^s_{sx_i}, \boldsymbol{\beta}\right) = \left[\begin{matrix}f&0\\0&f\end{matrix}\right]\mathbf{p}_d + \left[\begin{matrix}c_x\\c_y\end{matrix}\right]$$ $$\mathbf{p}_d = s\mathbf{p}_m$$ $$s = \frac{1}{\alpha d + (1-\alpha)z}, d = \sqrt{{\mathbf{t}^s_{sx_i}}^T\mathbf{t}^s_{sx_i}}$$ $$\mathbf{p}_m = \left[\begin{matrix}t_x\\t_y\end{matrix}\right]$$

Extended Unified Camera Model

Original paper

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}f&,&c_x&,&c_y&,&\alpha&,&\beta\end{matrix}\right]$$

$f$ = focal length

$c_x, c_y$ = image center

$\alpha$ = distortion parameter

$$\mathbf{P}\left(\mathbf{t}^s_{sx_i}, \boldsymbol{\beta}\right) = \left[\begin{matrix}f&0\\0&f\end{matrix}\right]\mathbf{p}_d + \left[\begin{matrix}c_x\\c_y\end{matrix}\right]$$ $$\mathbf{p}_d = s\mathbf{p}_m$$ $$s = \frac{1}{\alpha d + (1-\alpha)z}, d = \sqrt{\beta (t_x^2 + t_y^2) + t_z^2}$$ $$\mathbf{p}_m = \left[\begin{matrix}t_x\\t_y\end{matrix}\right]$$

Gyroscope

Gyroscopes transduce angular velocity motion to a 3-D measurement vector:

$\boldsymbol{\omega}^s_{ws}$ is the gyroscope's angular velocity w.r.t. the world resolved in the gyroscope frame.

$\mathbf{f}$ is measurement vector produced by the gyroscope.

$\boldsymbol{\beta}$ is a vector of intrinsics parameters.

$\mathbf{F}$ is the transduction function.

$$\mathbf{f} = \mathbf{F}\left(\boldsymbol{\omega}^s_{ws}, \boldsymbol{\beta}\right)$$

For the derivation of $\boldsymbol{\omega}^s_{ws}$, see here.

Isotropic Scale

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}s\end{matrix}\right]$$

$s$ = scale

$$\mathbf{F}\left(\boldsymbol{\omega}^s_{ws}, \boldsymbol{\beta}\right) = s\boldsymbol{\omega}^s_{ws}$$

Isotropic Scale and Bias

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}s&,&b_x&,&b_y&,&b_z\end{matrix}\right]$$

$s$ = scale

$$\mathbf{F}\left(\boldsymbol{\omega}^s_{ws}, \boldsymbol{\beta}\right) = s\boldsymbol{\omega}^s_{ws} + \left[\begin{matrix}b_x\\b_y\\b_z\end{matrix}\right]$$

VectorNav

Equation source

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}s_x&,&s_y&,&s_z&,&a_1&,&a_2&,&a_3&,&a_4&,&a_5&,&a_6&,&b_x&,&b_y&,&b_z\end{matrix}\right]$$

$s_x, s_y, s_z$ = scale

$a_1, ..., a_6$ = misalignment

$b_x, b_y, b_z$ = bias

$$\mathbf{F}\left(\boldsymbol{\omega}^s_{ws}, \boldsymbol{\beta}\right) = \left[\begin{matrix} s_x & 0 & 0\\\ 0 & s_y & 0\\\ 0 & 0 & s_z \end{matrix}\right] \left[\begin{matrix} 1 & a_1 & a_2\\\ a_3 & 1 & a_4\\\ a_5 & a_6 & 1 \end{matrix}\right] \boldsymbol{\omega}^s_{ws} + \left[\begin{matrix}b_x\\b_y\\b_z\end{matrix}\right]$$

Accelerometer

Accelerometers transduce the specific force at the sensor's location referenced to an inertial frame into a 3-D measurement vector:

$\mathbf{p}^s_{ws}$ is the specific force observed by the accelerometer w.r.t. the world resolved in the accelerometer's frame.

$\mathbf{f}$ is measurement vector produced by the gyroscope.

$\boldsymbol{\beta}$ is a vector of intrinsics parameters.

$\mathbf{F}$ is the transduction function.

$$\mathbf{f} = \mathbf{F}\left(\mathbf{p}^s_{ws}, \boldsymbol{\beta}\right)$$

For the derivation of $\mathbf{p}^s_{ws}$, see here.

Isotropic Scale

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}s\end{matrix}\right]$$

$s$ = scale

$$\mathbf{F}\left(\mathbf{p}^s_{ws}, \boldsymbol{\beta}\right) = s\mathbf{p}^s_{ws}$$

Isotropic Scale and Bias

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}s&,&b_x&,&b_y&,&b_z\end{matrix}\right]$$

$s$ = scale

$$\mathbf{F}\left(\mathbf{p}^s_{ws}, \boldsymbol{\beta}\right) = s\mathbf{p}^s_{ws} + \left[\begin{matrix}b_x\\b_y\\b_z\end{matrix}\right]$$

VectorNav

Equation source

Link to API

$$\boldsymbol{\beta} = \left[\begin{matrix}s_x&,&s_y&,&s_z&,&a_1&,&a_2&,&a_3&,&a_4&,&a_5&,&a_6&,&b_x&,&b_y&,&b_z\end{matrix}\right]$$

$s_x, s_y, s_z$ = scale

$a_1, ..., a_6$ = misalignment

$b_x, b_y, b_z$ = bias

$$\mathbf{F}\left(\mathbf{p}^s_{ws}, \boldsymbol{\beta}\right) = \left[\begin{matrix} s_x & 0 & 0\\\ 0 & s_y & 0\\\ 0 & 0 & s_z \end{matrix}\right] \left[\begin{matrix} 1 & a_1 & a_2\\\ a_3 & 1 & a_4\\\ a_5 & a_6 & 1 \end{matrix}\right] \mathbf{p}^s_{ws} + \left[\begin{matrix}b_x\\b_y\\b_z\end{matrix}\right]$$

Clone this wiki locally