pub struct RadTanCamera {
pub pinhole: PinholeParams,
pub distortion: DistortionModel,
}Expand description
A Radial-Tangential camera model with 9 intrinsic parameters.
Fields§
§pinhole: PinholeParams§distortion: DistortionModelImplementations§
Source§impl RadTanCamera
impl RadTanCamera
Sourcepub fn new(
pinhole: PinholeParams,
distortion: DistortionModel,
) -> Result<RadTanCamera, CameraModelError>
pub fn new( pinhole: PinholeParams, distortion: DistortionModel, ) -> Result<RadTanCamera, CameraModelError>
Creates a new Radial-Tangential (Brown-Conrady) camera.
§Arguments
pinhole- The pinhole parameters (fx, fy, cx, cy).distortion- The distortion model. This must beDistortionModel::BrownConradywith parameters { k1, k2, p1, p2, k3 }.
§Errors
Returns CameraModelError::InvalidParams if distortion is not DistortionModel::BrownConrady.
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 distortion parameters from point correspondences.
This method estimates the radial distortion coefficients [k1, k2, k3] using a linear least squares approach given 3D-2D point correspondences. Tangential distortion parameters (p1, p2) are set to 0.0. 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 RadTanCamera
impl CameraModel for RadTanCamera
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 in the camera frame to 2D image coordinates.
§Mathematical Formula
Combines radial distortion (k₁, k₂, k₃) and tangential distortion (p₁, p₂).
§Arguments
p_cam- The 3D point in the camera coordinate frame.
§Returns
Ok(uv)- The 2D image coordinates if valid.Err- If the point is at or behind the camera.
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
Iterative Newton-Raphson with Jacobian matrix:
- Start with the undistorted estimate.
- Compute distortion and Jacobian.
- Update estimate: p′ = p′ − J⁻¹ · f(p′).
- Repeat until convergence.
§Arguments
point_2d- The 2D point in image coordinates.
§Returns
Ok(ray)- The normalized 3D ray direction.Err- If the iteration fails to converge.
Source§fn jacobian_point(
&self,
p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
) -> <RadTanCamera as CameraModel>::PointJacobian
fn jacobian_point( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <RadTanCamera as CameraModel>::PointJacobian
Computes the Jacobian of the projection with respect to the 3D point coordinates (2×3).
§Mathematical Derivation
For the Radial-Tangential (Brown-Conrady) model, projection is:
x' = x/z, y' = y/z (normalized coordinates)
r² = x'² + y'²
radial = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
dx = 2·p₁·x'·y' + p₂·(r² + 2·x'²) (tangential distortion)
dy = p₁·(r² + 2·y'²) + 2·p₂·x'·y' (tangential distortion)
x'' = radial·x' + dx
y'' = radial·y' + dy
u = fx·x'' + cx
v = fy·y'' + cy§Chain Rule Application
This is the most complex Jacobian due to coupled radial + tangential distortion. The chain rule must be applied through multiple stages:
- ∂(x’,y’)/∂(x,y,z): Normalized coordinate derivatives
- ∂(x’‘,y’‘)/∂(x’,y’): Distortion derivatives (radial + tangential)
- ∂(u,v)/∂(x’‘,y’’): Final projection derivatives
Normalized coordinate derivatives (x’ = x/z, y’ = y/z):
∂x'/∂x = 1/z, ∂x'/∂y = 0, ∂x'/∂z = -x/z²
∂y'/∂x = 0, ∂y'/∂y = 1/z, ∂y'/∂z = -y/z²Distortion derivatives:
The distorted coordinates are: x’’ = radial·x’ + dx, y’’ = radial·y’ + dy
§Radial Distortion Component
radial = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
∂radial/∂r² = k₁ + 2k₂·r² + 3k₃·r⁴
∂r²/∂x' = 2x', ∂r²/∂y' = 2y'§Tangential Distortion Component
For dx = 2p₁x’y’ + p₂(r² + 2x’²):
∂dx/∂x' = 2p₁y' + p₂(2x' + 4x') = 2p₁y' + 6p₂x'
∂dx/∂y' = 2p₁x' + 2p₂y'For dy = p₁(r² + 2y’²) + 2p₂x’y’:
∂dy/∂x' = 2p₁x' + 2p₂y'
∂dy/∂y' = p₁(2y' + 4y') + 2p₂x' = 6p₁y' + 2p₂x'§Combined Distorted Coordinate Derivatives
For x’’ = radial·x’ + dx:
∂x''/∂x' = radial + x'·∂radial/∂r²·∂r²/∂x' + ∂dx/∂x'
= radial + x'·dradial_dr2·2x' + 2p₁y' + 6p₂x'
= radial + 2x'²·dradial_dr2 + 2p₁y' + 6p₂x'
∂x''/∂y' = x'·∂radial/∂r²·∂r²/∂y' + ∂dx/∂y'
= x'·dradial_dr2·2y' + 2p₁x' + 2p₂y'
= 2x'y'·dradial_dr2 + 2p₁x' + 2p₂y'For y’’ = radial·y’ + dy:
∂y''/∂x' = y'·∂radial/∂r²·∂r²/∂x' + ∂dy/∂x'
= y'·dradial_dr2·2x' + 2p₁x' + 2p₂y'
= 2x'y'·dradial_dr2 + 2p₁x' + 2p₂y'
∂y''/∂y' = radial + y'·∂radial/∂r²·∂r²/∂y' + ∂dy/∂y'
= radial + y'·dradial_dr2·2y' + 6p₁y' + 2p₂x'
= radial + 2y'²·dradial_dr2 + 6p₁y' + 2p₂x'Final projection derivatives (u = fx·x’’ + cx, v = fy·y’’ + cy):
∂u/∂x'' = fx, ∂u/∂y'' = 0
∂v/∂x'' = 0, ∂v/∂y'' = fyChain rule:
∂u/∂x = fx·(∂x''/∂x'·∂x'/∂x + ∂x''/∂y'·∂y'/∂x)
= fx·(∂x''/∂x'·1/z + 0)
= fx·∂x''/∂x'·1/z
∂u/∂y = fx·(∂x''/∂x'·∂x'/∂y + ∂x''/∂y'·∂y'/∂y)
= fx·(0 + ∂x''/∂y'·1/z)
= fx·∂x''/∂y'·1/z
∂u/∂z = fx·(∂x''/∂x'·∂x'/∂z + ∂x''/∂y'·∂y'/∂z)
= fx·(∂x''/∂x'·(-x'/z) + ∂x''/∂y'·(-y'/z))Similar derivations apply for ∂v/∂x, ∂v/∂y, ∂v/∂z.
§Matrix Form
J = [ ∂u/∂x ∂u/∂y ∂u/∂z ]
[ ∂v/∂x ∂v/∂y ∂v/∂z ]§References
- Brown, “Decentering Distortion of Lenses”, Photogrammetric Engineering 1966
- OpenCV Camera Calibration Documentation
- Hartley & Zisserman, “Multiple View Geometry”, Chapter 7
§Numerical Verification
Verified against numerical differentiation in test_jacobian_point_numerical().
Source§fn jacobian_intrinsics(
&self,
p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>,
) -> <RadTanCamera as CameraModel>::IntrinsicJacobian
fn jacobian_intrinsics( &self, p_cam: &Matrix<f64, Const<3>, Const<1>, ArrayStorage<f64, 3, 1>>, ) -> <RadTanCamera as CameraModel>::IntrinsicJacobian
Computes the Jacobian of the projection with respect to intrinsic parameters (2×9).
§Mathematical Derivation
The Radial-Tangential camera has 9 intrinsic parameters: [fx, fy, cx, cy, k₁, k₂, p₁, p₂, k₃]
§Projection Equations
x' = x/z, y' = y/z
r² = x'² + y'²
radial = 1 + k₁·r² + k₂·r⁴ + k₃·r⁶
dx = 2·p₁·x'·y' + p₂·(r² + 2·x'²)
dy = p₁·(r² + 2·y'²) + 2·p₂·x'·y'
x'' = radial·x' + dx
y'' = radial·y' + dy
u = fx·x'' + cx
v = fy·y'' + cy§Jacobian Structure
J = [ ∂u/∂fx ∂u/∂fy ∂u/∂cx ∂u/∂cy ∂u/∂k₁ ∂u/∂k₂ ∂u/∂p₁ ∂u/∂p₂ ∂u/∂k₃ ]
[ ∂v/∂fx ∂v/∂fy ∂v/∂cx ∂v/∂cy ∂v/∂k₁ ∂v/∂k₂ ∂v/∂p₁ ∂v/∂p₂ ∂v/∂k₃ ]Linear parameters (fx, fy, cx, cy):
∂u/∂fx = x'', ∂u/∂fy = 0, ∂u/∂cx = 1, ∂u/∂cy = 0
∂v/∂fx = 0, ∂v/∂fy = y'', ∂v/∂cx = 0, ∂v/∂cy = 1Radial distortion coefficients (k₁, k₂, k₃):
Each k_i affects the radial distortion component:
∂radial/∂k₁ = r²
∂radial/∂k₂ = r⁴
∂radial/∂k₃ = r⁶By chain rule (x’’ = radial·x’ + dx, y’’ = radial·y’ + dy):
∂x''/∂k₁ = x'·r²
∂x''/∂k₂ = x'·r⁴
∂x''/∂k₃ = x'·r⁶
∂y''/∂k₁ = y'·r²
∂y''/∂k₂ = y'·r⁴
∂y''/∂k₃ = y'·r⁶Then:
∂u/∂k₁ = fx·x'·r²
∂u/∂k₂ = fx·x'·r⁴
∂u/∂k₃ = fx·x'·r⁶
∂v/∂k₁ = fy·y'·r²
∂v/∂k₂ = fy·y'·r⁴
∂v/∂k₃ = fy·y'·r⁶Tangential distortion coefficients (p₁, p₂):
∂dx/∂p₁ = 2x'y', ∂dy/∂p₁ = r² + 2y'²
∂u/∂p₁ = fx·2x'y', ∂v/∂p₁ = fy·(r² + 2y'²)
∂dx/∂p₂ = r² + 2x'², ∂dy/∂p₂ = 2x'y'
∂u/∂p₂ = fx·(r² + 2x'²), ∂v/∂p₂ = fy·2x'y'Matrix form:
J = [ x'' 0 1 0 fx·x'·r² fx·x'·r⁴ fx·2x'y' fx·(r²+2x'²) fx·x'·r⁶ ]
[ 0 y'' 0 1 fy·y'·r² fy·y'·r⁴ fy·(r²+2y'²) fy·2x'y' fy·y'·r⁶ ]§References
- Brown, “Decentering Distortion of Lenses”, 1966
- OpenCV Camera Calibration Documentation
- Hartley & Zisserman, “Multiple View Geometry”, Chapter 7
§Numerical Verification
Verified in test_jacobian_intrinsics_numerical() with tolerance < 1e-5.
Source§fn validate_params(&self) -> Result<(), CameraModelError>
fn validate_params(&self) -> Result<(), CameraModelError>
Validates the camera parameters.
§Validation Rules
- fx, fy must be positive (> 0)
- fx, fy must be finite
- cx, cy must be finite
- k₁, k₂, p₁, p₂, k₃ must 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.
§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 parameters.
§Returns
The DistortionModel associated with this camera (typically DistortionModel::BrownConrady).
Source§fn get_model_name(&self) -> &'static str
fn get_model_name(&self) -> &'static str
Source§const INTRINSIC_DIM: usize = 9
const INTRINSIC_DIM: usize = 9
Source§type IntrinsicJacobian = Matrix<f64, Const<2>, Const<9>, ArrayStorage<f64, 2, 9>>
type IntrinsicJacobian = Matrix<f64, Const<2>, Const<9>, ArrayStorage<f64, 2, 9>>
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 RadTanCamera
impl Clone for RadTanCamera
Source§fn clone(&self) -> RadTanCamera
fn clone(&self) -> RadTanCamera
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for RadTanCamera
impl Debug for RadTanCamera
Source§impl From<&[f64]> for RadTanCamera
Creates a camera from a slice of intrinsic parameters.
impl From<&[f64]> for RadTanCamera
Creates a camera from a slice of intrinsic parameters.
§Layout
Expected parameter order: [fx, fy, cx, cy, k1, k2, p1, p2, k3]
§Panics
Panics if the slice has fewer than 9 elements.
Source§fn from(params: &[f64]) -> RadTanCamera
fn from(params: &[f64]) -> RadTanCamera
Source§impl From<&RadTanCamera> for [f64; 9]
Converts the camera parameters to a fixed-size array.
impl From<&RadTanCamera> for [f64; 9]
Converts the camera parameters to a fixed-size array.
§Layout
The parameters are ordered as: [fx, fy, cx, cy, k1, k2, p1, p2, k3]
Source§impl From<[f64; 9]> for RadTanCamera
Creates a camera from a fixed-size array of intrinsic parameters.
impl From<[f64; 9]> for RadTanCamera
Creates a camera from a fixed-size array of intrinsic parameters.
§Layout
Expected parameter order: [fx, fy, cx, cy, k1, k2, p1, p2, k3]
Source§impl PartialEq for RadTanCamera
impl PartialEq for RadTanCamera
impl Copy for RadTanCamera
impl StructuralPartialEq for RadTanCamera
Auto Trait Implementations§
impl Freeze for RadTanCamera
impl RefUnwindSafe for RadTanCamera
impl Send for RadTanCamera
impl Sync for RadTanCamera
impl Unpin for RadTanCamera
impl UnsafeUnpin for RadTanCamera
impl UnwindSafe for RadTanCamera
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.