Skip to main content

PinholeCamera

Struct PinholeCamera 

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

Pinhole camera model with 4 intrinsic parameters.

Fields§

§pinhole: PinholeParams§distortion: DistortionModel

Implementations§

Source§

impl PinholeCamera

Source

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

Creates a new Pinhole camera model.

§Arguments
  • pinhole - Pinhole camera parameters (fx, fy, cx, cy).
  • distortion - Distortion model (must be DistortionModel::None).
§Returns

Returns a new PinholeCamera instance if the parameters are valid.

§Errors

Returns CameraModelError if:

  • The distortion model is not None.
  • Parameters are invalid (e.g., negative focal length, infinite principal point).
§Example
use apex_camera_models::{PinholeCamera, PinholeParams, DistortionModel};

let pinhole = PinholeParams::new(500.0, 500.0, 320.0, 240.0)?;
let distortion = DistortionModel::None;
let camera = PinholeCamera::new(pinhole, distortion)?;

Trait Implementations§

Source§

impl CameraModel for PinholeCamera

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
u = fx · (x/z) + cx
v = fy · (y/z) + cy
§Arguments
  • p_cam - 3D point in camera coordinate frame (x, y, z).
§Returns

Returns the 2D image coordinates if valid.

§Errors

Returns CameraModelError::PointAtCameraCenter if the point is behind or at the camera center (z <= MIN_DEPTH).

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 in camera frame.

§Mathematical Formula
mx = (u - cx) / fx
my = (v - cy) / fy
ray = normalize([mx, my, 1])
§Arguments
  • point_2d - 2D point in image coordinates (u, v).
§Returns

Returns the normalized 3D ray direction.

§Errors

This function never fails for the simple pinhole model, but returns a Result for trait consistency.

Source§

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

Jacobian of projection w.r.t. 3D point coordinates (2×3).

Computes ∂π/∂p where π is the projection function and p = (x, y, z) is the 3D point.

§Mathematical Derivation

Given the pinhole projection model:

u = fx · (x/z) + cx
v = fy · (y/z) + cy

Derivatives:

∂u/∂x = fx/z,        ∂u/∂y = 0,     ∂u/∂z = -fx·x/z²
∂v/∂x = 0,           ∂v/∂y = fy/z,  ∂v/∂z = -fy·y/z²

Final Jacobian matrix (2×3):

J = [ ∂u/∂x   ∂u/∂y   ∂u/∂z  ]   [ fx/z    0      -fx·x/z² ]
    [ ∂v/∂x   ∂v/∂y   ∂v/∂z  ] = [  0     fy/z    -fy·y/z² ]
§Arguments
  • p_cam - 3D point in camera coordinate frame.
§Returns

Returns the 2x3 Jacobian matrix.

§Implementation Note

The implementation uses inv_z = 1/z and x_norm = x/z, y_norm = y/z to avoid redundant divisions and improve numerical stability.

§References
  • Hartley & Zisserman, “Multiple View Geometry”, Chapter 6
  • Standard perspective projection derivatives
  • Verified against numerical differentiation in tests
Source§

fn jacobian_intrinsics( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <PinholeCamera as CameraModel>::IntrinsicJacobian

Jacobian of projection w.r.t. intrinsic parameters (2×4).

Computes ∂π/∂K where K = [fx, fy, cx, cy] are the intrinsic parameters.

§Mathematical Derivation

The intrinsic parameters for the pinhole model are:

  • Focal lengths: fx, fy (scaling factors)
  • Principal point: cx, cy (image center offset)
§Projection Model Recap
u = fx · (x/z) + cx
v = fy · (y/z) + cy

Derivatives:

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

Final Jacobian matrix (2×4):

J = [ ∂u/∂fx  ∂u/∂fy  ∂u/∂cx  ∂u/∂cy ]
    [ ∂v/∂fx  ∂v/∂fy  ∂v/∂cx  ∂v/∂cy ]

  = [ x/z      0       1       0    ]
    [  0      y/z      0       1    ]
§Arguments
  • p_cam - 3D point in camera coordinate frame.
§Returns

Returns the 2x4 Intrinsic Jacobian matrix.

§Implementation Note

The implementation uses precomputed normalized coordinates:

  • x_norm = x/z
  • y_norm = y/z

This avoids redundant divisions and improves efficiency.

§References
  • Standard camera calibration literature
  • Hartley & Zisserman, “Multiple View Geometry”, Chapter 6
  • Verified against numerical differentiation in tests
Source§

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

Validates camera parameters.

§Validation Rules
  • fx and fy must be positive.
  • fx and fy must be finite.
  • cx and cy must be finite.
§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::None for pinhole).

Source§

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

Returns the string identifier for the camera model.

§Returns

The string "pinhole".

Source§

const INTRINSIC_DIM: usize = 4

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

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

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 PinholeCamera

Source§

fn clone(&self) -> PinholeCamera

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 PinholeCamera

Source§

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

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

impl From<&PinholeCamera> for [f64; 4]

Convert PinholeCamera to fixed-size parameter array.

Returns intrinsic parameters as [fx, fy, cx, cy]

Source§

fn from(camera: &PinholeCamera) -> [f64; 4]

Converts to this type from the input type.
Source§

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

Convert PinholeCamera to parameter vector.

Returns intrinsic parameters in the order: [fx, fy, cx, cy]

Source§

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

Converts to this type from the input type.
Source§

impl From<[f64; 4]> for PinholeCamera

Create PinholeCamera from fixed-size parameter array.

§Parameter Order

params = [fx, fy, cx, cy]

Source§

fn from(params: [f64; 4]) -> PinholeCamera

Converts to this type from the input type.
Source§

impl PartialEq for PinholeCamera

Source§

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

Create PinholeCamera from parameter slice.

Returns an error if the slice has fewer than 4 elements.

§Parameter Order

params = [fx, fy, cx, cy]

Source§

type Error = CameraModelError

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

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

Performs the conversion.
Source§

impl Copy for PinholeCamera

Source§

impl StructuralPartialEq for PinholeCamera

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,