Skip to main content

UcmCamera

Struct UcmCamera 

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

Unified Camera Model with 5 parameters.

Fields§

§pinhole: PinholeParams§distortion: DistortionModel

Implementations§

Source§

impl UcmCamera

Source

pub fn new( pinhole: PinholeParams, distortion: DistortionModel, ) -> Result<UcmCamera, CameraModelError>

Create a new Unified Camera Model (UCM) camera.

§Arguments
  • pinhole - Pinhole parameters (fx, fy, cx, cy).
  • distortion - MUST be DistortionModel::UCM with alpha.
§Returns

Returns a new UcmCamera instance if the distortion model matches.

§Errors

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

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 alpha parameter from point correspondences.

This method estimates the alpha 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 UcmCamera

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
d = √(x² + y² + z²)
denom = α·d + (1-α)·z
u = fx · (x/denom) + cx
v = fy · (y/denom) + cy
§Arguments
  • p_cam - 3D point in camera coordinate frame.
§Returns
  • Ok(uv) - 2D image coordinates if valid.
§Errors

Returns CameraModelError::PointAtCameraCenter if the projection condition fails or the denominator 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

Algebraic solution for UCM inverse projection.

§Arguments
  • point_2d - 2D point in image coordinates.
§Returns
  • Ok(ray) - Normalized 3D ray direction.
§Errors

Returns CameraModelError::PointOutsideImage if the unprojection condition fails.

Source§

fn jacobian_point( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <UcmCamera as CameraModel>::PointJacobian

Checks if a 3D point can be validly projected.

Computes the Jacobian of the projection function with respect to the 3D point in camera frame.

§Mathematical Derivation

The UCM projection model maps a 3D point p = (x, y, z) to 2D pixel coordinates (u, v).

Projection:

ρ = √(x² + y² + z²)
D = α·ρ + (1-α)·z
u = fx · (x/D) + cx
v = fy · (y/D) + cy

Jacobian:

Derivatives of D with respect to (x, y, z):

∂D/∂x = α · (x/ρ)
∂D/∂y = α · (y/ρ)
∂D/∂z = α · (z/ρ) + (1-α)

Using the quotient rule for u = fx · (x/D):

∂u/∂x = fx · (D - x·∂D/∂x) / D²
∂u/∂y = fx · (-x·∂D/∂y) / D²
∂u/∂z = fx · (-x·∂D/∂z) / D²

Similarly for v:

∂v/∂x = fy · (-y·∂D/∂x) / D²
∂v/∂y = fy · (D - y·∂D/∂y) / D²
∂v/∂z = fy · (-y·∂D/∂z) / D²
§Arguments
  • p_cam - 3D point in camera coordinate frame.
§Returns

Returns the 2x3 Jacobian matrix.

§References
  • Geyer & Daniilidis, “A Unifying Theory for Central Panoramic Systems”, ICCV 2000
  • Mei & Rives, “Single View Point Omnidirectional Camera Calibration from Planar Grids”, ICRA 2007
§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>>, ) -> <UcmCamera as CameraModel>::IntrinsicJacobian

Computes the Jacobian of the projection function with respect to intrinsic parameters.

§Mathematical Derivation

The UCM camera has 5 intrinsic parameters: θ = [fx, fy, cx, cy, α]

§Projection Model
u = fx · (x/D) + cx
v = fy · (y/D) + cy

Where D = α·ρ + (1-α)·z and ρ = √(x²+y²+z²)

§Jacobian Structure

Linear parameters (fx, fy, cx, cy):

∂u/∂fx = x/D,  ∂u/∂fy = 0,    ∂u/∂cx = 1,    ∂u/∂cy = 0
∂v/∂fx = 0,    ∂v/∂fy = y/D,  ∂v/∂cx = 0,    ∂v/∂cy = 1

Projection parameter α:

∂D/∂α = ρ - z
∂u/∂α = -fx · (x/D²) · (ρ - z)
∂v/∂α = -fy · (y/D²) · (ρ - z)
§Arguments
  • p_cam - 3D point in camera coordinate frame.
§Returns

Returns the 2x5 Intrinsic Jacobian matrix.

§References
  • Geyer & Daniilidis, “A Unifying Theory for Central Panoramic Systems”, ICCV 2000
§Verification

This Jacobian is verified against numerical differentiation in tests.

Source§

fn validate_params(&self) -> Result<(), CameraModelError>

Validates camera parameters.

§Validation Rules
  • fx, fy must be positive.
  • fx, fy must be finite.
  • cx, cy must be finite.
  • α must be in [0, 1].
§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::UCM).

Source§

fn get_model_name(&self) -> &'static str

Returns the string identifier for the camera model.

§Returns

The string "ucm".

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 UcmCamera

Source§

fn clone(&self) -> UcmCamera

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 UcmCamera

Source§

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

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

impl From<&UcmCamera> for [f64; 5]

Convert camera to fixed-size array of intrinsic parameters.

§Layout

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

Source§

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

Converts to this type from the input type.
Source§

impl From<&UcmCamera> 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, alpha]

Source§

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

Converts to this type from the input type.
Source§

impl From<[f64; 5]> for UcmCamera

Create camera from fixed-size array of intrinsic parameters.

§Layout

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

Source§

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

Converts to this type from the input type.
Source§

impl PartialEq for UcmCamera

Source§

fn eq(&self, other: &UcmCamera) -> 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 UcmCamera

Create camera from slice of intrinsic parameters.

§Layout

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

§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<UcmCamera, <UcmCamera as TryFrom<&[f64]>>::Error>

Performs the conversion.
Source§

impl Copy for UcmCamera

Source§

impl StructuralPartialEq for UcmCamera

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,