pub struct FovCamera {
pub pinhole: PinholeParams,
pub distortion: DistortionModel,
}Expand description
FOV camera model with 5 parameters.
Fields§
§pinhole: PinholeParams§distortion: DistortionModelImplementations§
Source§impl FovCamera
impl FovCamera
Sourcepub fn new(
pinhole: PinholeParams,
distortion: DistortionModel,
) -> Result<FovCamera, CameraModelError>
pub fn new( pinhole: PinholeParams, distortion: DistortionModel, ) -> Result<FovCamera, CameraModelError>
Create a new Field-of-View (FOV) camera.
§Arguments
pinhole- Pinhole parameters (fx, fy, cx, cy).distortion- MUST beDistortionModel::FOVwith parameterw.
§Returns
Returns a new FovCamera instance if the distortion model matches.
§Errors
Returns CameraModelError::InvalidParams if distortion is not DistortionModel::FOV.
Sourcepub fn linear_estimation(
&mut self,
points_3d: &Matrix<f64, Const<3>, Dyn, VecStorage<f64, Const<3>, Dyn>>,
points_2d: &Matrix<f64, Const<2>, Dyn, VecStorage<f64, Const<2>, Dyn>>,
) -> Result<(), CameraModelError>
pub fn linear_estimation( &mut self, points_3d: &Matrix<f64, Const<3>, Dyn, VecStorage<f64, Const<3>, Dyn>>, points_2d: &Matrix<f64, Const<2>, Dyn, VecStorage<f64, Const<2>, Dyn>>, ) -> Result<(), CameraModelError>
Performs linear estimation to initialize the w parameter from point correspondences.
This method estimates the w parameter using a linear least squares approach
given 3D-2D point correspondences. It assumes the intrinsic parameters (fx, fy, cx, cy)
are already set.
§Arguments
points_3d: Matrix3xX- 3D points in camera coordinates (each column is a point) points_2d: Matrix2xX- Corresponding 2D points in image coordinates
§Returns
Returns Ok(()) on success or a CameraModelError if the estimation fails.
Trait Implementations§
Source§impl CameraModel for FovCamera
impl CameraModel for FovCamera
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
Uses atan-based radial distortion with FOV parameter w.
§Arguments
p_cam- 3D point in camera coordinate frame.
§Returns
Ok(uv)- 2D image coordinates if valid.
§Errors
Returns CameraModelError::ProjectionOutOfBounds if z is too small.
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.
§Algorithm
Trigonometric inverse using sin/cos relationships.
§Arguments
point_2d- 2D point in image coordinates.
§Returns
Ok(ray)- Normalized 3D ray direction.
§Errors
This model does not explicitly fail unprojection unless internal math errors occur, in which case it propagates them.
Source§fn jacobian_point(
&self,
p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
) -> <FovCamera as CameraModel>::PointJacobian
fn jacobian_point( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <FovCamera as CameraModel>::PointJacobian
Jacobian of projection w.r.t. 3D point coordinates (2×3).
§Mathematical Derivation
For the FOV camera model, projection is defined as:
r = √(x² + y²)
α = 2·tan(w/2)·r / z
atan_wrd = atan(α)
rd = atan_wrd / (r·w) (if r > 0)
rd = 2·tan(w/2) / w (if r ≈ 0)
mx = x · rd
my = y · rd
u = fx · mx + cx
v = fy · my + cy§Jacobian Structure
Computing ∂u/∂p and ∂v/∂p where p = (x, y, z):
J_point = [ ∂u/∂x ∂u/∂y ∂u/∂z ]
[ ∂v/∂x ∂v/∂y ∂v/∂z ]Chain rule for u = fx · x · rd + cx and v = fy · y · rd + cy:
∂u/∂x = fx · ∂(x·rd)/∂x = fx · (rd + x · ∂rd/∂x)
∂u/∂y = fx · ∂(x·rd)/∂y = fx · x · ∂rd/∂y
∂u/∂z = fx · ∂(x·rd)/∂z = fx · x · ∂rd/∂z
∂v/∂x = fy · ∂(y·rd)/∂x = fy · y · ∂rd/∂x
∂v/∂y = fy · ∂(y·rd)/∂y = fy · (rd + y · ∂rd/∂y)
∂v/∂z = fy · ∂(y·rd)/∂z = fy · y · ∂rd/∂zComputing ∂rd/∂x, ∂rd/∂y, ∂rd/∂z for r > 0 (rd = atan(α) / (r·w), α = 2·tan(w/2)·r / z):
∂rd/∂r = [∂atan/∂α · ∂α/∂r · r·w - atan(α) · w] / (r·w)²
= [1/(1+α²) · 2·tan(w/2)/z · r·w - atan(α) · w] / (r·w)²
∂rd/∂z = ∂atan/∂α · ∂α/∂z / (r·w)
= 1/(1+α²) · (-2·tan(w/2)·r/z²) / (r·w)Then using ∂r/∂x = x/r and ∂r/∂y = y/r:
∂rd/∂x = ∂rd/∂r · ∂r/∂x = ∂rd/∂r · x/r
∂rd/∂y = ∂rd/∂r · ∂r/∂y = ∂rd/∂r · y/r
∂rd/∂z = (computed directly above)Near optical axis (r < ε): rd = 2·tan(w/2) / w is constant, so ∂rd/∂x = ∂rd/∂y = ∂rd/∂z = 0:
J_point = [ fx·rd 0 0 ]
[ 0 fy·rd 0 ]§Arguments
p_cam- 3D point in camera coordinate frame.
§Returns
Returns the 2x3 Jacobian matrix.
§References
- Devernay & Faugeras, “Straight lines have to be straight”, Machine Vision and Applications 2001
- Zhang et al., “Fisheye Camera Calibration Using Principal Point Constraints”, PAMI 2012
§Numerical Verification
This analytical Jacobian is verified against numerical differentiation in
test_jacobian_point_numerical() with tolerance < 1e-6.
Source§fn jacobian_intrinsics(
&self,
p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
) -> <FovCamera as CameraModel>::IntrinsicJacobian
fn jacobian_intrinsics( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <FovCamera as CameraModel>::IntrinsicJacobian
Jacobian of projection w.r.t. intrinsic parameters (2×5).
§Mathematical Derivation
The FOV camera has 5 intrinsic parameters: [fx, fy, cx, cy, w]
§Projection Equations
u = fx · mx + cx
v = fy · my + cywhere mx = x · rd and my = y · rd, with:
rd = atan(2·tan(w/2)·r/z) / (r·w) (for r > 0)
rd = 2·tan(w/2) / w (for r ≈ 0)§Jacobian Structure
Intrinsic Jacobian (2×5):
J = [ ∂u/∂fx ∂u/∂fy ∂u/∂cx ∂u/∂cy ∂u/∂w ]
[ ∂v/∂fx ∂v/∂fy ∂v/∂cx ∂v/∂cy ∂v/∂w ]§Linear Parameters (fx, fy, cx, cy)
These appear linearly in the projection equations:
∂u/∂fx = mx, ∂u/∂fy = 0, ∂u/∂cx = 1, ∂u/∂cy = 0
∂v/∂fx = 0, ∂v/∂fy = my, ∂v/∂cx = 0, ∂v/∂cy = 1§Distortion Parameter (w)
The parameter w affects the distortion factor rd. We need ∂rd/∂w.
§Case 1: r > 0 (Non-Optical Axis)
Starting from:
α = 2·tan(w/2)·r / z
rd = atan(α) / (r·w)Taking derivatives:
∂α/∂w = 2·sec²(w/2)·(1/2)·r/z = sec²(w/2)·r/zwhere sec²(w/2) = 1 + tan²(w/2).
Using the quotient rule for rd = atan(α) / (r·w):
∂rd/∂w = [∂atan(α)/∂w · r·w - atan(α) · r] / (r·w)²
= [1/(1+α²) · ∂α/∂w · r·w - atan(α) · r] / (r·w)²
= [sec²(w/2)·r²·w/z·(1/(1+α²)) - atan(α)·r] / (r²·w²)Simplifying:
∂rd/∂w = [∂atan(α)/∂α · ∂α/∂w · r·w - atan(α)·r] / (r·w)²§Case 2: r ≈ 0 (Near Optical Axis)
When r ≈ 0, we use rd = 2·tan(w/2) / w.
Using the quotient rule:
∂rd/∂w = [2·sec²(w/2)·(1/2)·w - 2·tan(w/2)] / w²
= [sec²(w/2)·w - 2·tan(w/2)] / w²§Final Jacobian w.r.t. w
Once we have ∂rd/∂w, we compute:
∂u/∂w = fx · ∂(x·rd)/∂w = fx · x · ∂rd/∂w
∂v/∂w = fy · ∂(y·rd)/∂w = fy · y · ∂rd/∂w§Matrix Form
The complete Jacobian matrix is:
J = [ mx 0 1 0 fx·x·∂rd/∂w ]
[ 0 my 0 1 fy·y·∂rd/∂w ]where mx = x·rd and my = y·rd.
§Arguments
p_cam- 3D point in camera coordinate frame.
§Returns
Returns the 2x5 Intrinsic Jacobian matrix.
§References
- Devernay & Faugeras, “Straight lines have to be straight”, Machine Vision and Applications 2001
- Hughes et al., “Rolling Shutter Motion Deblurring”, CVPR 2010 (uses FOV model)
§Numerical Verification
This analytical Jacobian is verified against numerical differentiation in
test_jacobian_intrinsics_numerical() with tolerance < 1e-4.
§Notes
The FOV parameter w controls the field of view angle. Typical values range from 0.5 (narrow FOV) to π (hemispheric fisheye). The derivative ∂rd/∂w captures how changes in the FOV parameter affect the radial distortion mapping.
Source§fn validate_params(&self) -> Result<(), CameraModelError>
fn validate_params(&self) -> Result<(), CameraModelError>
Validates camera parameters.
§Validation Rules
- fx, fy must be positive (> 0)
- fx, fy must be finite
- cx, cy must be finite
- w must be in (0, π]
§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.
§Returns
A PinholeParams struct containing the focal lengths (fx, fy) and principal point (cx, cy).
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::FOV).
Source§fn get_model_name(&self) -> &'static str
fn get_model_name(&self) -> &'static str
Source§const INTRINSIC_DIM: usize = 5
const INTRINSIC_DIM: usize = 5
Source§type IntrinsicJacobian = Matrix<f64, Const<2>, Const<5>, ArrayStorage<f64, 2, 5>>
type IntrinsicJacobian = Matrix<f64, Const<2>, Const<5>, ArrayStorage<f64, 2, 5>>
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§fn jacobian_pose(
&self,
p_world: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
pose: &SE3,
) -> (Self::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, ) -> (Self::PointJacobian, Matrix<f64, Const<3>, Const<6>, ArrayStorage<f64, 3, 6>>)
Source§impl From<&[f64]> for FovCamera
Create camera from slice of intrinsic parameters.
impl From<&[f64]> for FovCamera
Create camera from slice of intrinsic parameters.
Source§impl From<&FovCamera> for [f64; 5]
Convert camera to fixed-size array of intrinsic parameters.
impl From<&FovCamera> for [f64; 5]
Convert camera to fixed-size array of intrinsic parameters.
§Layout
The parameters are ordered as: [fx, fy, cx, cy, w]
Source§impl From<[f64; 5]> for FovCamera
Create camera from fixed-size array of intrinsic parameters.
impl From<[f64; 5]> for FovCamera
Create camera from fixed-size array of intrinsic parameters.
§Layout
Expected parameter order: [fx, fy, cx, cy, w]
impl Copy for FovCamera
impl StructuralPartialEq for FovCamera
Auto Trait Implementations§
impl Freeze for FovCamera
impl RefUnwindSafe for FovCamera
impl Send for FovCamera
impl Sync for FovCamera
impl Unpin for FovCamera
impl UnsafeUnpin for FovCamera
impl UnwindSafe for FovCamera
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.