A Cal3_S2
represents the simple 5-parameter camera calibration model Hartley & Zisserman, 2004[1]. This model includes parameters for the focal lengths (), the skew factor (), and the principal point (). It does not model lens distortion. The calibration matrix is defined as:
This model is based on the assumption of a pinhole camera model. The main purpose of this model is for instrinsic conversions between image pixel coordinates in the image sensor frame and the normalized image coordinates . The normalized image coordinates (also called intrinsic coordinates) are coordinates on a canonical image plane that is unit focal length away from the aperture point. In other words, given any 3D point based on the camera frame coordinates, a Cal3_S2
model can handle conversions between and , where
%pip install --quiet gtsam-develop
import gtsam
import numpy as np
from gtsam import Cal3_S2, Point2
Initialization¶
A Cal3_S2
can be initialized in several ways. Initializing with no arguments yields a calibration model with the identity matrix as the calibration matrix. You can also construct a particular model with either individual values for the focal lengths, skew, and principal point, or pass all parameters in a 5-vector.
# Default constructor: fx=1, fy=1, s=0, u0=0, v0=0
cal0 = Cal3_S2()
print("Default constructor (fx=1, fy=1, s=0, u0=0, v0=0):")
print(cal0)
print(f"fx: {cal0.fx()}, fy: {cal0.fy()}, s: {cal0.skew()}, u0: {cal0.px()}, v0: {cal0.py()}\n")
# From individual parameters: fx, fy, s, u0, v0
fx, fy, s, u0, v0 = 1500.0, 1600.0, 0.1, 320.0, 240.0
cal1 = Cal3_S2(fx, fy, s, u0, v0)
print("From parameters (fx, fy, s, u0, v0):")
print(cal1)
print(f"fx: {cal1.fx()}, fy: {cal1.fy()}, s: {cal1.skew()}, u0: {cal1.px()}, v0: {cal1.py()}\n")
# From a 5-vector [fx, fy, s, u0, v0]
cal_vector = np.array([1500.0, 1600.0, 0.1, 320.0, 240.0])
cal2 = Cal3_S2(cal_vector)
print("From a 5-vector [fx, fy, s, u0, v0]:")
print(cal2)
print(f"fx: {cal2.fx()}, fy: {cal2.fy()}, s: {cal2.skew()}, u0: {cal2.px()}, v0: {cal2.py()}\n")
Default constructor (fx=1, fy=1, s=0, u0=0, v0=0):
Cal3_S2[
1, 0, 0;
0, 1, 0;
0, 0, 1
]
fx: 1.0, fy: 1.0, s: 0.0, u0: 0.0, v0: 0.0
From parameters (fx, fy, s, u0, v0):
Cal3_S2[
1500, 0.1, 320;
0, 1600, 240;
0, 0, 1
]
fx: 1500.0, fy: 1600.0, s: 0.1, u0: 320.0, v0: 240.0
From a 5-vector [fx, fy, s, u0, v0]:
Cal3_S2[
1500, 0.1, 320;
0, 1600, 240;
0, 0, 1
]
fx: 1500.0, fy: 1600.0, s: 0.1, u0: 320.0, v0: 240.0
Additionally, you can construct a calibration model with the field-of-view (FOV), in degrees, and the image width and height. The resulting model assumes zero skew and unit aspect (i.e. pixel densities ). The resulting calibration model is expected to have
# From FOV, width, and height
fov, w, h = 120, 100, 50
cal3 = Cal3_S2(fov, w, h)
print("From FOV (degrees) and image width and height:")
print(cal3)
print(f"fx: {cal3.fx()}, fy: {cal3.fy()}, s: {cal3.skew()}, u0: {cal3.px()}, v0: {cal3.py()}\n")
From FOV (degrees) and image width and height:
Cal3_S2[
28.8675, 0, 50;
0, 28.8675, 25;
0, 0, 1
]
fx: 28.867513459481298, fy: 28.867513459481298, s: 0.0, u0: 50.0, v0: 25.0
Properties¶
Main Parameters¶
The 5 main parameters of the Cal3_S2
model can be accessed using the following member functions:
fx()
: Returns , which is the effective focal length of the camera scaled by the pixel density along the x-axis.fy()
: Returns , which is the effective focal length of the camera scaled by the pixel density along the y-axis.skew()
: Returns the skew factor , where θ is the concave angle between the two skewed image axes.px()
: Returns , the x-coordinate of the principal point with respect to the image sensor frame.py()
: Returns , the y-coordinate of the principal point with respect to the image sensor frame.principalPoint()
: Returns anumpy.ndarray
with 2 elements depicting the principal point. The returned vector follow the form .vector()
: Returns anumpy.ndarray
with 5 elements depicting a vectorized form of the calibration parameters. The returned 5-vector follow the following form .
fx, fy, s, u0, v0 = 1500.0, 1600.0, 0.1, 320.0, 240.0
cal4 = Cal3_S2(fx, fy, s, u0, v0)
print("Calibration object call:")
print(f"fx: {cal4.fx()}")
print(f"fy: {cal4.fy()}")
print(f"s: {cal4.skew()}")
print(f"u0: {cal4.px()}")
print(f"v0: {cal4.py()}")
print(f"Principal point (u0, v0): {cal4.principalPoint()}")
print(f"Calibration vector [fx, fy, s, u0, v0]: {cal4.vector()}")
Calibration object call:
fx: 1500.0
fy: 1600.0
s: 0.1
u0: 320.0
v0: 240.0
Principal point (u0, v0): [320. 240.]
Calibration vector [fx, fy, s, u0, v0]: [1.5e+03 1.6e+03 1.0e-01 3.2e+02 2.4e+02]
Derived Properties¶
Cal3_S2
also has some member functions to retrieve useful derived properties:
aspectRatio()
: Returns the aspect ratio computed with (which is also equivalent to ).K()
: Returns anumpy.ndarray
with a dimension of representing the calibration matrix for the model.inverse()
: Returns the inverted calibration matrix .
print(f"Aspect ratio: {cal4.aspectRatio()}")
print(f"K matrix:\n{cal4.K()}")
print(f"inv(K) matrix:\n{cal4.inverse()}")
Aspect ratio: 0.9375
K matrix:
[[1.5e+03 1.0e-01 3.2e+02]
[0.0e+00 1.6e+03 2.4e+02]
[0.0e+00 0.0e+00 1.0e+00]]
inv(K) matrix:
[[ 6.66666667e-04 -4.16666667e-08 -2.13323333e-01]
[ 0.00000000e+00 6.25000000e-04 -1.50000000e-01]
[ 0.00000000e+00 0.00000000e+00 1.00000000e+00]]
Basic Operations¶
calibrate()
¶
Cal3_S2
provides member functions to convert points between normalized image coordinates and pixel coordinates.
The calibrate(p)
member function converts a 2D point p
in image pixel coordinates to normalized image coordinates . This member function effectively implements the formula
where and are homogeneous representations of and , respectively.
fx, fy, s, u0, v0 = 1000.0, 1000.0, 0, 320.0, 240.0
cal_model = Cal3_S2(fx, fy, s, u0, v0)
print("Converting top-left pixel coordinates to normalized pixel coordinates: ")
p_pixels = Point2(0, 0)
print(f"Pixel point: {p_pixels}")
p_norm = cal_model.calibrate(p_pixels)
print(f"Calibrated (normalized) point: {p_norm}")
Converting top-left pixel coordinates to normalized pixel coordinates:
Pixel point: [0. 0.]
Calibrated (normalized) point: [-0.32 -0.24]
print("Converting princpal point pixel coordinates to normalized pixel coordinates: ")
p_pixels = Point2(320, 240)
print(f"Pixel point: {p_pixels}")
p_norm = cal_model.calibrate(p_pixels)
print(f"Calibrated (normalized) point: {p_norm}")
Converting princpal point pixel coordinates to normalized pixel coordinates:
Pixel point: [320. 240.]
Calibrated (normalized) point: [0. 0.]
The calibrate()
member function can optionally compute Jacobians with respect to the calibration parameters (Dcal
) and the input point (Dp
). This is useful for optimization tasks. Note that matrices you pass in must be column-major arrays with the correct shape.
# Jacobians for calibrate(p_pixels)
Dcal_calibrate = np.zeros((2, 5), order='F')
Dp_calibrate = np.zeros((2, 2), order='F')
_ = cal_model.calibrate(p_pixels, Dcal_calibrate, Dp_calibrate) # Calibrated point is returned, assign to _
print(f"Jacobian Dcal_calibrate:\n{Dcal_calibrate}")
print(f"Jacobian Dp_calibrate:\n{Dp_calibrate}")
Jacobian Dcal_calibrate:
[[-0. 0. -0. -0.001 0. ]
[ 0. -0. 0. 0. -0.001]]
Jacobian Dp_calibrate:
[[ 0.001 -0. ]
[ 0. 0.001]]
uncalibrate()
¶
The uncalibrate(p)
member function converts a 2D point p
from normalized image coordinates back to image pixel coordinates . This is the inverse operation of calibrate()
and effectively implements the formula
p_pixels_recovered = cal_model.uncalibrate(p_norm)
print(f"Normalized point: {p_norm}")
print(f"Uncalibrated (pixel) point: {p_pixels_recovered}")
Normalized point: [0. 0.]
Uncalibrated (pixel) point: [320. 240.]
The uncalibrate()
member function can also optionally compute Jacobians with respect to the calibration parameters (Dcal
) and the input point (Dp
). Likewise, the matrices you pass in must be column-major arrays with the correct shape.
# Jacobians for calibrate(p_norm)
Dcal_calibrate = np.zeros((2, 5), order='F')
Dp_calibrate = np.zeros((2, 2), order='F')
_ = cal_model.uncalibrate(p_norm, Dcal_calibrate, Dp_calibrate) # Calibrated point is returned, assign to _
print(f"Jacobian Dcal_calibrate:\n{Dcal_calibrate}")
print(f"Jacobian Dp_calibrate:\n{Dp_calibrate}")
Jacobian Dcal_calibrate:
[[0. 0. 0. 1. 0.]
[0. 0. 0. 0. 1.]]
Jacobian Dp_calibrate:
[[1000. 0.]
[ 0. 1000.]]
Manifold Operations¶
Cal3_S2
, like many geometric types in GTSAM, is treated as a manifold in order to optimize over it. This means it supports operations like retract()
(moving on the manifold given a tangent vector) and localCoordinates()
(finding the tangent vector between two points on the manifold). These operations enable gradient-based optimization by applying updates in the tangent space of the manifold.
print("Original cal_model:")
print(cal_model)
# Retract: Apply a delta to the calibration parameters
delta_vec = np.array([10.0, 20.0, 0.05, 1.0, -1.0])
cal_retracted = cal_model.retract(delta_vec)
print(f"Delta vector: {delta_vec}")
print("Retracted cal_retracted:")
print(cal_retracted)
# Local coordinates: Find the delta between two calibrations
local_coords = cal_model.localCoordinates(cal_retracted)
print("\nLocal coordinates from cal_model to cal_retracted:")
print(local_coords)
Original cal_model:
Cal3_S2[
1000, 0, 320;
0, 1000, 240;
0, 0, 1
]
Delta vector: [10. 20. 0.05 1. -1. ]
Retracted cal_retracted:
Cal3_S2[
1010, 0.05, 321;
0, 1020, 239;
0, 0, 1
]
Local coordinates from cal_model to cal_retracted:
[10. 20. 0.05 1. -1. ]
Additional Resources¶
The following curated resources provide detailed explanations of the camera calibration process. If you found any parts of this user guide to be confusing, we recommend getting started by reviewing these resources first:
Article(s)¶
- “Camera Intrinsics: Axis skew” by Ashima Athri
Video(s)¶
- “Linear Camera Model | Camera Calibration” by Dr. Shree Nayar from Columbia University
- “Computer Vision: The Camera Matrix” by Michael Prasthofer
Source¶
See ch. 6 6.1, pp. 153–157.
- Hartley, R., & Zisserman, A. (2004). Multiple View Geometry in Computer Vision. Cambridge University Press. 10.1017/cbo9780511811685