Skip to content

Commit 857b079

Browse files
Cheng Pengmeta-codesync[bot]
authored andcommitted
add camera intrinsics and sensor measurement models
Summary: add camera intrinsics and sensor measurement model same as gen1 website Reviewed By: kongchen1992 Differential Revision: D84959620 fbshipit-source-id: f978708178761cce52120ef14aaa3e9831ea9d8b
1 parent 960eee4 commit 857b079

File tree

9 files changed

+185
-1
lines changed

9 files changed

+185
-1
lines changed

website/docs-technical-specs/device/cad.mdx

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
---
2-
sidebar_position: 3
2+
sidebar_position: 4
33
title: CAD File Downloads
44
---
55
The table below outlines the 8 size versions for the Gen2 design, included are both states for the hinge: open and closed. Also, we do include a portion with camera FOV’s.

website/docs-technical-specs/device/calibration.mdx

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ The following table shows which calibration data is available for each sensor ty
3434
| **Speakers** | `LSPK`, `RSPK` | ✅ Sensitivity (dBV) ||
3535

3636
### Camera Projection Models
37+
Details of the camera intrinsics model can be found in [calibration insight](/technical-specs/device/calibration_insights/camera_intrinsics_models)
3738

3839
- **FisheyeRadTanThinPrism**: Used for RGB and SLAM cameras
3940
- Parameters: focal length (f), principal point (cx, cy), radial distortion (k0-k5), tangential distortion (p0, p1), thin prism (s0-s2)
@@ -42,6 +43,7 @@ The following table shows which calibration data is available for each sensor ty
4243
- Parameters: focal lengths (fx, fy), principal point (cx, cy), Kannala-Brandt distortion coefficients (kb0-kb3)
4344

4445
### IMU Calibration Components
46+
Details of the IMU models can be found in [calibration insight](/technical-specs/device/calibration_insights/sensor_measurement_model)
4547

4648
- **Accelerometer**: Bias offset (m/s²) and 3x3 rectification matrix for scale/cross-axis corrections
4749
- **Gyroscope**: Bias offset (rad/s), rectification matrix, and G-sensitivity matrix
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
{
2+
"label": "Calibration insights",
3+
"position": 3
4+
}
Lines changed: 143 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,143 @@
1+
---
2+
sidebar_position: 1
3+
title: Camera Intrinsic Models
4+
---
5+
# Camera Intrinsic Models for Project Aria devices
6+
7+
This page provides an overview of the intrinsic models used by RGB, Eye Tracking and Mono Scene (aka SLAM) cameras in Project Aria glasses.
8+
9+
A camera intrinsic model maps between a 3D world point in the camera coordinate and its corresponding 2D pixel on the sensor. It supports mapping from the 3D point to the pixel (projection) and from the pixel to the ray connecting the point and the camera's optical center.
10+
11+
Our projection models are based on polar coordinates of 3D world points. Given a 3D world point in the device frame $\mathbf{P}_d$, we first transform it to the camera's local frame
12+
$$
13+
\mathbf{P}_c = (x, y, z) = T_\text{device}^\text{camera}\mathbf{P}_d
14+
$$
15+
16+
the corresponding polar coordinates $\Phi = (\theta, \varphi)$ that satisfies
17+
$$
18+
x/z = \tan(\theta)\cos(\varphi), \quad
19+
y/z = \tan(\theta)\sin(\varphi).
20+
$$
21+
22+
We assume the camera has a single optical center and thus all points of the same polar coordinate maps to the same 2D pixel $\mathbf{p}$:
23+
$$
24+
\mathbf{p} = f(\phi)
25+
$$
26+
Here $f$ is the camera projection model.
27+
28+
Inversely, we can unproject from a 2D camera pixel to the polar coordinate by
29+
$$
30+
\Phi = f^{-1}(\mathbf{p})
31+
$$
32+
33+
In Aria we support four types of project models, Linear, Spherical, KannalaBrandtK3, and FisheyeRadTanThinPrism. The linear camera model are standard textbook intrinsic models and good for image rectification. However, cameras on the Aria glasses all have fisheye lenses, and spherical camera model are much better approximations for these glasses. In order to calibrate the camera lenses at a high quality, we use two more sophisticated camera models to add modeling of radial and tangential distortions.
34+
35+
![Image](/img/docs-technical-specs/calibration/linear.png)
36+
![Image](/img/docs-technical-specs/calibration/spherical.png)
37+
![Image](/img/docs-technical-specs/calibration/kb3.png)
38+
![Image](/img/docs-technical-specs/calibration/fisheye.png)
39+
40+
The next table shows which model is used for each type of Aria camera:
41+
42+
| Camera Type | Intrinsics Model |
43+
|---------------------------|-------------------------|
44+
| Slam Camera | FisheyeRadTanThinPrism |
45+
| Rgb Camera | FisheyeRadTanThinPrism |
46+
| Eye-Tracking Camera | KannalaBrandtK3 |
47+
48+
## The linear camera model
49+
The linear camera model (a.k.a pinhole model) is parametrized by 4 coefficients : f_x, f_y, c_x, c_y.
50+
51+
$(f_x, f_y)$ are the focal lengths, and $c_x, c_y$ are the coordinate of the projection of the optical axis.
52+
It maps from world point $(x,y,z)$ to 2D camera pixel $\mathbf{p}=(u, v)$ with the following formulae.
53+
$$
54+
u = f_x x/z + c_x \\
55+
v = f_y y/z + c_y
56+
$$
57+
Or, in polar coordinates:
58+
$$
59+
u = f_x tan(\theta) \cos(\varphi) + c_x, \\
60+
v = f_y tan(\theta) \sin(\varphi) + c_y.
61+
$$
62+
63+
Inversely, we can unproject from 2D camera pixel $\mathbf{p}=(u, v)$ to the homogeneous coordinate of the world point by
64+
$$
65+
x/z=(u-c_x)/f_x, \\
66+
y/z=(v-c_y)/f_y.
67+
$$
68+
The linear camera model preserves linearity in 3D space, thus straight lines in the real world are supposed to look straight under the linear camera model.
69+
70+
## The spherical camera model
71+
72+
The spherical camera model is, similarly from the linear camera model parametrized by 4 coefficients : f_x, f_y, c_x, c_y.
73+
The pixel coordinates are linear to solid angles rather than the homography coordinate system.
74+
The projection function can be written in polar coordinates
75+
$$
76+
u = f_x \theta \cos(\varphi) + c_x, \\
77+
v = f_y \theta \sin(\varphi) + c_y.
78+
$$
79+
Note the difference from the linear camera model — under spherical projection, 3D straight lines look curved in images.
80+
81+
Inversely, we can unproject from 2D camera pixel $\mathbf{p}=(u, v)$ to the homogeneous coordinate of the world point by
82+
$$
83+
\theta = \sqrt{(u - c_x)^2/f_x^2 + (v - c_y)^2/f_y^2}, \\
84+
\varphi = \arctan((u - c_x)/f_x, (v - c_y)/f_y).
85+
$$
86+
87+
## The KannalaBrandtK3 (KB3) model
88+
89+
The KannalaBrandtK3 model adds radial distortion to the linear model
90+
$$
91+
u = f_x r(\theta) \cos(\varphi) + c_x, \quad
92+
v = f_y r(\theta) \sin(\varphi) + c_y.
93+
$$
94+
where
95+
$$
96+
r(\theta) = \theta + k_0 \theta^3 + k_1 \theta^5 + k_2 \theta^7 + k_3 \theta^9 + ...
97+
$$
98+
In KannalaBrandtK3 model we use a 9-th order polynomial with four radial distortion parameters $k_0, ... k_3$.
99+
100+
To unproject from camera pixel $(u, v)$ to the world point $(\theta, \varphi)$, we first compute
101+
$$
102+
\varphi = \arctan((u - c_x)/f_x, (v - c_y)/f_y) \\
103+
r(\theta) = \sqrt{(u - c_x)^2/f_x^2 + (v - c_y)^2/f_y^2}
104+
$$
105+
Then we use Newton method to inverse the function $r(\theta)$ to compute $\theta$. See the code [here](https://github.com/facebookresearch/projectaria_tools/blob/afad1fe09dd1d89eee55ceb95ba1f2f577f9c606/core/calibration/camera_projections/KannalaBrandtK3.h#L131-L147).
106+
107+
## The Fisheye62 model
108+
109+
The Fisheye62 model adds tangential distortion on top of the KB3 model parametrized by two new coefficients: p_0 p_1.
110+
$$
111+
u = f_x . (u_r + t_x(u_r, v_r)) + c_x, \\
112+
v = f_y . (v_r + t_y(u_r, v_r)) + c_y.
113+
$$
114+
where
115+
$$
116+
u_r = r(\theta) \cos(\varphi), \\
117+
v_r = r(\theta) \sin(\varphi).
118+
$$
119+
and
120+
$$
121+
t_x(u_r, v_r) = p_0(2 u_r^2 + r(\theta)^2) + 2p_1u_rv_r, \\
122+
t_y(u_r, v_r) = p_1(2 v_r^2 + r(\theta)^2) + 2p_0u_rv_r.
123+
$$
124+
125+
To unproject from camera pixel $(u, v)$ to the world point $(\theta, \varphi)$, we first use Newton method to compute $u_r$ and $v_r$ from $(u - c_x)/f_x$ and $(v - cy)/f_y$, and then compute $(\theta, \varphi)$ using the above KB3 unproject method.
126+
127+
## The FisheyeRadTanThinPrism (Fisheye624) model
128+
129+
The FisheyeRadTanThinPrism (also called Fisheye624 in file and codebase) models thin-prism distortion (noted $tp$) on top of the Fisheye62 model above.
130+
Its parametrization contains 4 additional coefficients: s_0 s_1 s_2 s_3. The projection function writes:
131+
$$
132+
u = f_x \cdot (u_r + t_x(u_r, v_r) + tp_x(u_r, v_r)) + c_x, \\
133+
v = f_y \cdot (v_r + t_y(u_r, v_r) + tp_y(u_r, v_r)) + c_y.
134+
$$
135+
u_r, v_r, t_x, t_y are defined as in the Fisheye62 model, while $tp_x$ and $tp_y$ are defined as:
136+
$$
137+
tp_x(u_r, v_r) = s_0 r(\theta)^2 + s_1 r(\theta)^4, \\
138+
tp_y(u_r, v_r) = s_2 r(\theta)^2 + s_3 r(\theta)^4.
139+
$$
140+
141+
To unproject from camera pixel $(u, v)$ to the world point $(\theta, \varphi)$, we first use Newton method to compute $u_r$ and $v_r$ from $(u - c_x)/f_x$ and $(v - cy)/f_y$, and then compute $(\theta, \varphi)$ using the above KB3 unproject method.
142+
143+
Note that in practice, in our codebase and calibration file we assume $f_x$ and $f_y$ are equal.
Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
---
2+
sidebar_position: 2
3+
title: Sensor Measurement Model
4+
---
5+
6+
# Sensor Measurement Models in Project Aria Devices
7+
8+
This page provides an overview of how Project Aria device sensor measurements are modeled for IMU, magnetometer, barometer and audio.
9+
## IMUs
10+
11+
For IMUs, we employ an affine model where the value from the readout of accelerometer $s_a$ or gyroscope $s_g$, is compensated to obtain a "real" acceleration $a$ and angular velocity $\omega$ by
12+
$$
13+
a = M_a^{-1}(s_a - b_a) \qquad
14+
\omega = M_g^{-1}(s_g - b_g)
15+
$$
16+
$M_a$ and $M_g$ are assumed to be upper triangular so that there is no global rotation from the imu body frame to the accelerometer frame.
17+
18+
Inversely, we can simulate the sensor read-out from acceleration or angular velocity by
19+
$$
20+
s_a = M_a a + b_a \qquad
21+
s_g = M_g \omega + b_g
22+
$$
23+
24+
When the read-out signal exceeds a threshold, the signal saturates. Saturation limits are sensor dependent and referenced in the following table for accelerometer and gyrometers.
25+
26+
||accel-left | accel-right| gyro-left | gyro-right|
27+
|--|--|--|--|--|
28+
|saturation|8g|16g|2000|2000|
29+
30+
31+
## Magnetometer, barometer and audio
32+
33+
Similar to the IMU rectification model, the sensor readouts for magnetometer, barometer, and audio data are modeled as linear to the real $r$ (magnetic field, air pressure and sound intensity).
34+
35+
Audio specifically is bias only.
84 KB
Loading
67.4 KB
Loading
12.3 KB
Loading
78 KB
Loading

0 commit comments

Comments
 (0)