pub struct BALPinholeCameraStrict {
pub f: f64,
pub distortion: DistortionModel,
}Expand description
Strict BAL camera model matching Snavely’s Bundler convention.
This camera model uses EXACTLY 3 intrinsic parameters matching the BAL file format:
- Single focal length (f): fx = fy
- Two radial distortion coefficients (k1, k2)
- NO principal point (cx = cy = 0 by convention)
This matches the intrinsic parameterization used by:
- Ceres Solver bundle adjustment examples
- GTSAM bundle adjustment
- Original Bundler software
§Parameters
f: Single focal length in pixels (fx = fy = f)k1: First radial distortion coefficientk2: Second radial distortion coefficient
§Projection Model
For a 3D point p_cam = (x, y, z) in camera frame where z < 0:
x_n = x / (-z)
y_n = y / (-z)
r² = x_n² + y_n²
distortion = 1 + k1*r² + k2*r⁴
x_d = x_n * distortion
y_d = y_n * distortion
u = f * x_d (no cx offset)
v = f * y_d (no cy offset)§Usage
This camera model should be used for bundle adjustment problems that read BAL format files, to ensure parameter compatibility and avoid degenerate optimization (extra DOF from fx≠fy or non-zero principal point).
Fields§
§f: f64Single focal length (fx = fy = f)
distortion: DistortionModelImplementations§
Source§impl BALPinholeCameraStrict
impl BALPinholeCameraStrict
Sourcepub fn new(
pinhole: PinholeParams,
distortion: DistortionModel,
) -> Result<BALPinholeCameraStrict, CameraModelError>
pub fn new( pinhole: PinholeParams, distortion: DistortionModel, ) -> Result<BALPinholeCameraStrict, CameraModelError>
Creates a new strict BAL pinhole camera with distortion.
§Arguments
pinhole- Pinhole parameters. MUST havefx == fyandcx == cy == 0for strict BAL format.distortion- MUST beDistortionModel::Radialwithk1andk2.
§Returns
Returns a new BALPinholeCameraStrict instance if parameters satisfy the strict BAL constraints.
§Errors
Returns CameraModelError::InvalidParams if:
pinhole.fx != pinhole.fy(strict BAL requires single focal length).pinhole.cx != 0.0orpinhole.cy != 0.0(strict BAL has no principal point offset).distortionis notDistortionModel::Radial.
§Example
use apex_camera_models::{BALPinholeCameraStrict, PinholeParams, DistortionModel};
let pinhole = PinholeParams::new(500.0, 500.0, 0.0, 0.0)?;
let distortion = DistortionModel::Radial { k1: -0.1, k2: 0.01 };
let camera = BALPinholeCameraStrict::new(pinhole, distortion)?;Sourcepub fn new_no_distortion(
f: f64,
) -> Result<BALPinholeCameraStrict, CameraModelError>
pub fn new_no_distortion( f: f64, ) -> Result<BALPinholeCameraStrict, CameraModelError>
Creates a strict BAL pinhole camera without distortion (k1=0, k2=0).
This is a convenience constructor for the common case of no distortion.
§Arguments
f- The single focal length in pixels.
§Returns
Returns a new BALPinholeCameraStrict instance with zero distortion.
§Errors
Returns CameraModelError if the focal length is invalid (e.g., negative).
Trait Implementations§
Source§impl CameraModel for BALPinholeCameraStrict
impl CameraModel for BALPinholeCameraStrict
Source§fn project(
&self,
p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
) -> Result<Matrix<f64, Const<2>, Const<1>, ArrayStorage<f64, 2, 1>>, CameraModelError>
fn project( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> Result<Matrix<f64, Const<2>, Const<1>, ArrayStorage<f64, 2, 1>>, CameraModelError>
Projects a 3D point to 2D image coordinates.
§Mathematical Formula
BAL/Bundler convention (camera looks down negative Z axis):
x_n = x / (−z)
y_n = y / (−z)
r² = x_n² + y_n²
r⁴ = (r²)²
d = 1 + k₁·r² + k₂·r⁴
u = f · x_n · d
v = f · y_n · d§Arguments
p_cam- 3D point in camera coordinate frame (x, y, z).
§Returns
Returns the 2D image coordinates (u, v) if valid.
§Errors
Returns CameraModelError::ProjectionOutOfBounds if point is not in front of camera (z ≥ 0).
Source§fn jacobian_point(
&self,
p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
) -> <BALPinholeCameraStrict as CameraModel>::PointJacobian
fn jacobian_point( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <BALPinholeCameraStrict as CameraModel>::PointJacobian
Computes the Jacobian of the projection function with respect to the 3D point in camera frame.
§Mathematical Derivation
The projection function maps a 3D point p_cam = (x, y, z) to 2D pixel coordinates (u, v).
Normalized coordinates (BAL uses negative Z convention):
x_n = x / (-z) = x * inv_neg_z
y_n = y / (-z) = y * inv_neg_zJacobian of normalized coordinates:
∂x_n/∂x = inv_neg_z = -1/z
∂x_n/∂y = 0
∂x_n/∂z = x_n * inv_neg_z
∂y_n/∂x = 0
∂y_n/∂y = inv_neg_z = -1/z
∂y_n/∂z = y_n * inv_neg_zRadial distortion:
The radial distance squared and distortion factor:
r² = x_n² + y_n²
r⁴ = (r²)²
d(r²) = 1 + k1·r² + k2·r⁴Distorted coordinates:
x_d = x_n · d(r²)
y_d = y_n · d(r²)§Derivatives of r² and d(r²):
∂(r²)/∂x_n = 2·x_n
∂(r²)/∂y_n = 2·y_n
∂d/∂(r²) = k1 + 2·k2·r²§Jacobian of distorted coordinates w.r.t. normalized:
∂x_d/∂x_n = ∂(x_n · d)/∂x_n = d + x_n · (∂d/∂(r²)) · (∂(r²)/∂x_n)
= d + x_n · (k1 + 2·k2·r²) · 2·x_n
∂x_d/∂y_n = x_n · (∂d/∂(r²)) · (∂(r²)/∂y_n)
= x_n · (k1 + 2·k2·r²) · 2·y_n
∂y_d/∂x_n = y_n · (k1 + 2·k2·r²) · 2·x_n
∂y_d/∂y_n = d + y_n · (k1 + 2·k2·r²) · 2·y_nPixel coordinates (strict BAL has no principal point):
u = f · x_d
v = f · y_dChain rule:
J = ∂(u,v)/∂(x_d,y_d) · ∂(x_d,y_d)/∂(x_n,y_n) · ∂(x_n,y_n)/∂(x,y,z)Final results:
∂u/∂x = f · (∂x_d/∂x_n · ∂x_n/∂x + ∂x_d/∂y_n · ∂y_n/∂x)
= f · (∂x_d/∂x_n · inv_neg_z)
∂u/∂y = f · (∂x_d/∂y_n · inv_neg_z)
∂u/∂z = f · (∂x_d/∂x_n · ∂x_n/∂z + ∂x_d/∂y_n · ∂y_n/∂z)
∂v/∂x = f · (∂y_d/∂x_n · inv_neg_z)
∂v/∂y = f · (∂y_d/∂y_n · inv_neg_z)
∂v/∂z = f · (∂y_d/∂x_n · ∂x_n/∂z + ∂y_d/∂y_n · ∂y_n/∂z)§Arguments
p_cam- 3D point in camera coordinate frame.
§Returns
Returns the 2x3 Jacobian matrix.
§References
- Snavely et al., “Photo Tourism: Exploring Photo Collections in 3D”, SIGGRAPH 2006
- Agarwal et al., “Bundle Adjustment in the Large”, ECCV 2010
- Bundle Adjustment in the Large Dataset
§Verification
This Jacobian is verified against numerical differentiation in tests.
Source§fn jacobian_pose(
&self,
p_world: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
pose: &SE3,
) -> (<BALPinholeCameraStrict as CameraModel>::PointJacobian, Matrix<f64, Const<3>, Const<6>, ArrayStorage<f64, 3, 6>>)
fn jacobian_pose( &self, p_world: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, pose: &SE3, ) -> (<BALPinholeCameraStrict as CameraModel>::PointJacobian, Matrix<f64, Const<3>, Const<6>, ArrayStorage<f64, 3, 6>>)
Jacobian of projection w.r.t. camera pose (2×6).
Computes ∂π/∂δξ where π is the projection and δξ ∈ se(3) is the pose perturbation.
§Mathematical Derivation
Given a 3D point in world frame p_world and camera pose pose (camera-to-world transformation),
we need the Jacobian ∂π/∂δξ.
§Camera Coordinate Transformation
The pose is a camera-to-world SE(3) transformation: T_cw = (R, t) where:
- R ∈ SO(3): rotation from camera to world
- t ∈ ℝ³: translation of camera origin in world frame
To transform from world to camera, we use the inverse:
p_cam = T_cw^{-1} · p_world = R^T · (p_world - t)§SE(3) Right Perturbation
Right perturbation on SE(3) for δξ = [δρ; δθ] ∈ ℝ⁶:
T' = T ∘ Exp(δξ)Where δξ = [δρ; δθ] with:
- δρ ∈ ℝ³: translation perturbation (in camera frame)
- δθ ∈ ℝ³: rotation perturbation (axis-angle in camera frame)
§Perturbation Effect on Transformed Point
Under right perturbation T’ = T ∘ Exp([δρ; δθ]):
R' = R · Exp(δθ) ≈ R · (I + [δθ]×)
t' ≈ t + R · δρ (for small δθ, V(δθ) ≈ I)Then the transformed point becomes:
p_cam' = (R')^T · (p_world - t')
= (I - [δθ]×) · R^T · (p_world - t - R · δρ)
≈ (I - [δθ]×) · R^T · (p_world - t) - (I - [δθ]×) · δρ
≈ (I - [δθ]×) · p_cam - δρ
= p_cam - [δθ]× · p_cam - δρ
= p_cam + p_cam × δθ - δρ
= p_cam + [p_cam]× · δθ - δρ
= p_cam + [p_cam]× · δθ - δρWhere [v]× denotes the skew-symmetric matrix (cross-product matrix).
§Jacobian of p_cam w.r.t. Pose Perturbation
From the above derivation:
∂p_cam/∂[δρ; δθ] = [-I | [p_cam]×]This is a 3×6 matrix where:
- First 3 columns (translation): -I (identity with negative sign)
- Last 3 columns (rotation): [p_cam]× (skew-symmetric matrix of p_cam)
§Chain Rule
The final Jacobian is:
∂(u,v)/∂ξ = ∂(u,v)/∂p_cam · ∂p_cam/∂ξ§Arguments
p_world- 3D point in world coordinate frame.pose- The camera pose in SE(3).
§Returns
Returns a tuple (d_uv_d_pcam, d_pcam_d_pose):
d_uv_d_pcam: 2×3 Jacobian of projection w.r.t. point in camera framed_pcam_d_pose: 3×6 Jacobian of camera point w.r.t. pose perturbation
§References
- Barfoot & Furgale, “Associating Uncertainty with Three-Dimensional Poses for Use in Estimation Problems”, IEEE Trans. Robotics 2014
- Solà et al., “A Micro Lie Theory for State Estimation in Robotics”, arXiv:1812.01537, 2018
- Blanco, “A tutorial on SE(3) transformation parameterizations and on-manifold optimization”, Technical Report 2010
§Verification
This Jacobian is verified against numerical differentiation in tests.
Source§fn jacobian_intrinsics(
&self,
p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
) -> <BALPinholeCameraStrict as CameraModel>::IntrinsicJacobian
fn jacobian_intrinsics( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <BALPinholeCameraStrict as CameraModel>::IntrinsicJacobian
Computes the Jacobian of the projection function with respect to intrinsic parameters.
§Mathematical Derivation
The strict BAL camera has EXACTLY 3 intrinsic parameters:
θ = [f, k1, k2]Where:
- f: Single focal length (fx = fy = f)
- k1, k2: Radial distortion coefficients
- NO principal point (cx = cy = 0 by convention)
§Projection Model
Recall the projection equations:
x_n = x / (-z), y_n = y / (-z)
r² = x_n² + y_n²
d(r²; k1, k2) = 1 + k1·r² + k2·r⁴
x_d = x_n · d(r²; k1, k2)
y_d = y_n · d(r²; k1, k2)
u = f · x_d
v = f · y_d§Jacobian w.r.t. Focal Length (f)
The focal length appears only in the final step:
∂u/∂f = ∂(f · x_d)/∂f = x_d
∂v/∂f = ∂(f · y_d)/∂f = y_d§Jacobian w.r.t. Distortion Coefficients (k1, k2)
The distortion coefficients affect the distortion function d(r²):
∂d/∂k1 = r²
∂d/∂k2 = r⁴Using the chain rule:
∂u/∂k1 = ∂(f · x_d)/∂k1 = f · ∂x_d/∂k1
= f · ∂(x_n · d)/∂k1
= f · x_n · (∂d/∂k1)
= f · x_n · r²
∂u/∂k2 = f · x_n · (∂d/∂k2)
= f · x_n · r⁴Similarly for v:
∂v/∂k1 = f · y_n · r²
∂v/∂k2 = f · y_n · r⁴§Complete Jacobian Matrix (2×3)
∂/∂f ∂/∂k1 ∂/∂k2
∂u/∂θ = [x_d, f·x_n·r², f·x_n·r⁴]
∂v/∂θ = [y_d, f·y_n·r², f·y_n·r⁴]§Arguments
p_cam- 3D point in camera coordinate frame.
§Returns
Returns the 2x3 Intrinsic Jacobian matrix (w.r.t [f, k1, k2]).
§References
- Agarwal et al., “Bundle Adjustment in the Large”, ECCV 2010, Section 3
- Ceres Solver: Bundle Adjustment Tutorial
- Triggs et al., “Bundle Adjustment - A Modern Synthesis”, Vision Algorithms: Theory and Practice, 2000
§Notes
This differs from the general BALPinholeCamera which has 6 parameters (fx, fy, cx, cy, k1, k2).
The strict BAL format enforces fx=fy and cx=cy=0 to match the original Bundler software
and standard BAL dataset files, reducing the intrinsic dimensionality from 6 to 3.
§Verification
This Jacobian is verified against numerical differentiation in tests.
Source§fn unproject(
&self,
point_2d: &Matrix<f64, Const<2>, Const<1>, ArrayStorage<f64, 2, 1>>,
) -> Result<Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, CameraModelError>
fn unproject( &self, point_2d: &Matrix<f64, Const<2>, Const<1>, ArrayStorage<f64, 2, 1>>, ) -> Result<Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, CameraModelError>
Unprojects a 2D image point to a 3D ray.
§Mathematical Formula
Iterative undistortion followed by back-projection:
x_d = u / f
y_d = v / f
// iterative undistortion to recover x_n, y_n
ray = normalize([x_n, y_n, −1])Uses Newton-Raphson iteration to solve the radial distortion polynomial for undistorted normalized coordinates, then converts to a unit ray.
§Arguments
point_2d- 2D point in image coordinates (u, v).
§Returns
Returns the normalized 3D ray direction.
Source§fn validate_params(&self) -> Result<(), CameraModelError>
fn validate_params(&self) -> Result<(), CameraModelError>
Validates camera parameters.
§Validation Rules
- Focal length
fmust be positive. - Focal length
fmust be finite. - Distortion coefficients
k1,k2must be finite.
§Errors
Returns CameraModelError if any parameter violates validation rules.
Source§fn get_pinhole_params(&self) -> PinholeParams
fn get_pinhole_params(&self) -> PinholeParams
Returns the pinhole parameters of the camera.
Note: For strict BAL cameras, fx = fy = f and cx = cy = 0.
§Returns
A PinholeParams struct where fx = fy = f and cx = cy = 0.
Source§fn get_distortion(&self) -> DistortionModel
fn get_distortion(&self) -> DistortionModel
Returns the distortion model and parameters of the camera.
§Returns
The DistortionModel associated with this camera (typically DistortionModel::Radial with k1, k2).
Source§fn get_model_name(&self) -> &'static str
fn get_model_name(&self) -> &'static str
Source§const INTRINSIC_DIM: usize = 3
const INTRINSIC_DIM: usize = 3
Source§type IntrinsicJacobian = Matrix<f64, Const<2>, Const<3>, ArrayStorage<f64, 2, 3>>
type IntrinsicJacobian = Matrix<f64, Const<2>, Const<3>, ArrayStorage<f64, 2, 3>>
Source§type PointJacobian = Matrix<f64, Const<2>, Const<3>, ArrayStorage<f64, 2, 3>>
type PointJacobian = Matrix<f64, Const<2>, Const<3>, ArrayStorage<f64, 2, 3>>
Source§impl Clone for BALPinholeCameraStrict
impl Clone for BALPinholeCameraStrict
Source§fn clone(&self) -> BALPinholeCameraStrict
fn clone(&self) -> BALPinholeCameraStrict
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for BALPinholeCameraStrict
impl Debug for BALPinholeCameraStrict
Source§impl From<&[f64]> for BALPinholeCameraStrict
Create camera from slice of intrinsic parameters.
impl From<&[f64]> for BALPinholeCameraStrict
Create camera from slice of intrinsic parameters.
§Layout
Expected parameter order: [f, k1, k2]
§Panics
Panics if the slice has fewer than 3 elements or if validation fails.
Source§fn from(params: &[f64]) -> BALPinholeCameraStrict
fn from(params: &[f64]) -> BALPinholeCameraStrict
Source§impl From<&BALPinholeCameraStrict> for [f64; 3]
Convert camera to fixed-size array of intrinsic parameters.
impl From<&BALPinholeCameraStrict> for [f64; 3]
Convert camera to fixed-size array of intrinsic parameters.
§Layout
The parameters are ordered as: [f, k1, k2]
Source§impl From<[f64; 3]> for BALPinholeCameraStrict
Create camera from fixed-size array of intrinsic parameters.
impl From<[f64; 3]> for BALPinholeCameraStrict
Create camera from fixed-size array of intrinsic parameters.
§Layout
Expected parameter order: [f, k1, k2]
Source§impl PartialEq for BALPinholeCameraStrict
impl PartialEq for BALPinholeCameraStrict
impl Copy for BALPinholeCameraStrict
impl StructuralPartialEq for BALPinholeCameraStrict
Auto Trait Implementations§
impl Freeze for BALPinholeCameraStrict
impl RefUnwindSafe for BALPinholeCameraStrict
impl Send for BALPinholeCameraStrict
impl Sync for BALPinholeCameraStrict
impl Unpin for BALPinholeCameraStrict
impl UnsafeUnpin for BALPinholeCameraStrict
impl UnwindSafe for BALPinholeCameraStrict
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<T> DistributionExt for Twhere
T: ?Sized,
impl<T> DistributionExt for Twhere
T: ?Sized,
Source§impl<T> Instrument for T
impl<T> Instrument for T
Source§fn instrument(self, span: Span) -> Instrumented<Self>
fn instrument(self, span: Span) -> Instrumented<Self>
Source§fn in_current_span(self) -> Instrumented<Self>
fn in_current_span(self) -> Instrumented<Self>
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left is true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
self into a Left variant of Either<Self, Self>
if into_left(&self) returns true.
Converts self into a Right variant of Either<Self, Self>
otherwise. Read moreSource§impl<T> Pointable for T
impl<T> Pointable for T
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.