Skip to main content

FovCamera

Struct FovCamera 

Source
pub struct FovCamera {
    pub pinhole: PinholeParams,
    pub distortion: DistortionModel,
}
Expand description

FOV camera model with 5 parameters.

Fields§

§pinhole: PinholeParams§distortion: DistortionModel

Implementations§

Source§

impl FovCamera

Source

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 be DistortionModel::FOV with parameter w.
§Returns

Returns a new FovCamera instance if the distortion model matches.

§Errors

Returns CameraModelError::InvalidParams if distortion is not DistortionModel::FOV.

Source

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

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>

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>

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

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/∂z

Computing ∂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

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 + cy

where 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/z

where 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>

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

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

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

Returns the string identifier for the camera model.

§Returns

The string "fov".

Source§

const INTRINSIC_DIM: usize = 5

Number of intrinsic parameters (compile-time constant).
Source§

type IntrinsicJacobian = Matrix<f64, Const<2>, Const<5>, ArrayStorage<f64, 2, 5>>

Jacobian type for intrinsics: 2 × INTRINSIC_DIM.
Source§

type PointJacobian = Matrix<f64, Const<2>, Const<3>, ArrayStorage<f64, 2, 3>>

Jacobian type for 3D point: 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>>)

Jacobian of projection w.r.t. camera pose (SE3). Read more
Source§

fn project_batch( &self, points_cam: &Matrix<f64, Const<3>, Dyn, VecStorage<f64, Const<3>, Dyn>>, ) -> Matrix<f64, Const<2>, Dyn, VecStorage<f64, Const<2>, Dyn>>

Batch projection of multiple 3D points to 2D image coordinates. Read more
Source§

impl Clone for FovCamera

Source§

fn clone(&self) -> FovCamera

Returns a duplicate of the value. Read more
1.0.0 (const: unstable) · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for FovCamera

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result<(), Error>

Formats the value using the given formatter. Read more
Source§

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§

fn from(camera: &FovCamera) -> [f64; 5]

Converts to this type from the input type.
Source§

impl From<&FovCamera> for Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>

Convert camera to dynamic vector of intrinsic parameters.

§Layout

The parameters are ordered as: [fx, fy, cx, cy, w]

Source§

fn from( camera: &FovCamera, ) -> Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>

Converts to this type from the input type.
Source§

impl From<[f64; 5]> for FovCamera

Create camera from fixed-size array of intrinsic parameters.

§Layout

Expected parameter order: [fx, fy, cx, cy, w]

Source§

fn from(params: [f64; 5]) -> FovCamera

Converts to this type from the input type.
Source§

impl PartialEq for FovCamera

Source§

fn eq(&self, other: &FovCamera) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 (const: unstable) · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl TryFrom<&[f64]> for FovCamera

Create camera from slice of intrinsic parameters.

§Layout

Expected parameter order: [fx, fy, cx, cy, w]

§Panics

Panics if the slice has fewer than 5 elements.

Source§

type Error = CameraModelError

The type returned in the event of a conversion error.
Source§

fn try_from( params: &[f64], ) -> Result<FovCamera, <FovCamera as TryFrom<&[f64]>>::Error>

Performs the conversion.
Source§

impl Copy for FovCamera

Source§

impl StructuralPartialEq for FovCamera

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> ByRef<T> for T

Source§

fn by_ref(&self) -> &T

Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> DistributionExt for T
where T: ?Sized,

Source§

fn rand<T>(&self, rng: &mut (impl Rng + ?Sized)) -> T
where Self: Distribution<T>,

Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T> Instrument for T

Source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
Source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> IntoEither for T

Source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts 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 more
Source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts 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 more
Source§

impl<T> Pointable for T

Source§

const ALIGN: usize

The alignment of pointer.
Source§

type Init = T

The type for initializers.
Source§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
Source§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
Source§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
Source§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V

Source§

impl<T> WithSubscriber for T

Source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

impl<T> Boilerplate for T
where T: Copy + Send + Sync + Debug + PartialEq + 'static,

Source§

impl<T, U> Imply<T> for U
where T: ?Sized, U: ?Sized,

Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,