pub struct PinholeCamera {
pub pinhole: PinholeParams,
pub distortion: DistortionModel,
}Expand description
Pinhole camera model with 4 intrinsic parameters.
Fields§
§pinhole: PinholeParams§distortion: DistortionModelImplementations§
Source§impl PinholeCamera
impl PinholeCamera
Sourcepub fn new(
pinhole: PinholeParams,
distortion: DistortionModel,
) -> Result<PinholeCamera, CameraModelError>
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 beDistortionModel::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
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>
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>
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
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) + cyDerivatives:
∂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
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) + cyDerivatives:
∂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 = 1Final 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/zy_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>
fn validate_params(&self) -> Result<(), CameraModelError>
Validates camera parameters.
§Validation Rules
fxandfymust be positive.fxandfymust be finite.cxandcymust 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.
§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::None for pinhole).
Source§fn get_model_name(&self) -> &'static str
fn get_model_name(&self) -> &'static str
Source§const INTRINSIC_DIM: usize = 4
const INTRINSIC_DIM: usize = 4
Source§type IntrinsicJacobian = Matrix<f64, Const<2>, Const<4>, ArrayStorage<f64, 2, 4>>
type IntrinsicJacobian = Matrix<f64, Const<2>, Const<4>, ArrayStorage<f64, 2, 4>>
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 Clone for PinholeCamera
impl Clone for PinholeCamera
Source§fn clone(&self) -> PinholeCamera
fn clone(&self) -> PinholeCamera
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for PinholeCamera
impl Debug for PinholeCamera
Source§impl From<&[f64]> for PinholeCamera
Create PinholeCamera from parameter slice.
impl From<&[f64]> for PinholeCamera
Create PinholeCamera from parameter slice.
Source§fn from(params: &[f64]) -> PinholeCamera
fn from(params: &[f64]) -> PinholeCamera
Source§impl From<&PinholeCamera> for [f64; 4]
Convert PinholeCamera to fixed-size parameter array.
impl From<&PinholeCamera> for [f64; 4]
Convert PinholeCamera to fixed-size parameter array.
Returns intrinsic parameters as [fx, fy, cx, cy]
Source§impl From<[f64; 4]> for PinholeCamera
Create PinholeCamera from fixed-size parameter array.
impl From<[f64; 4]> for PinholeCamera
Create PinholeCamera from fixed-size parameter array.
§Parameter Order
params = [fx, fy, cx, cy]
Source§impl PartialEq for PinholeCamera
impl PartialEq for PinholeCamera
impl Copy for PinholeCamera
impl StructuralPartialEq for PinholeCamera
Auto Trait Implementations§
impl Freeze for PinholeCamera
impl RefUnwindSafe for PinholeCamera
impl Send for PinholeCamera
impl Sync for PinholeCamera
impl Unpin for PinholeCamera
impl UnsafeUnpin for PinholeCamera
impl UnwindSafe for PinholeCamera
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.