pub struct Intrinsics {
pub principal_point: (Float, Float),
pub focal: (Float, Float),
pub skew: Float,
}
Expand description
Intrinsic parameters of a pinhole camera model.
Fields§
§principal_point: (Float, Float)
Principal point (in the optical center axis) of the camera.
focal: (Float, Float)
Focal length in pixels along both axes.
skew: Float
Skew of the camera, usually 0.0.
Implementations§
Source§impl Intrinsics
impl Intrinsics
Sourcepub fn matrix(&self) -> Affine2<Float>
pub fn matrix(&self) -> Affine2<Float>
Equivalent matrix representation of intrinsic parameters.
Sourcepub fn multi_res(self, n: usize) -> Vec<Self>
pub fn multi_res(self, n: usize) -> Vec<Self>
Generate a multi-resolution vector of intrinsic parameters. Each level corresponds to a camera with half resolution.
Sourcepub fn half_res(&self) -> Self
pub fn half_res(&self) -> Self
Compute intrinsic parameters of a camera with half resolution.
Since the (0,0) coordinates correspond the center of the first pixel, and not its top left corner, a shift of 0.5 is performed for the principal point before and after the resolution scaling.
Sourcepub fn project(&self, point: Point3) -> Vec3
pub fn project(&self, point: Point3) -> Vec3
Project a 3D point in camera coordinates into a 2D homogeneous image point.
Sourcepub fn back_project(&self, point: Point2, depth: Float) -> Point3
pub fn back_project(&self, point: Point2, depth: Float) -> Point3
Back project a pixel with depth info into a 3D point in camera coordinates.
Trait Implementations§
Source§impl Clone for Intrinsics
impl Clone for Intrinsics
Source§fn clone(&self) -> Intrinsics
fn clone(&self) -> Intrinsics
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl Debug for Intrinsics
impl Debug for Intrinsics
Source§impl PartialEq for Intrinsics
impl PartialEq for Intrinsics
impl StructuralPartialEq for Intrinsics
Auto Trait Implementations§
impl Freeze for Intrinsics
impl RefUnwindSafe for Intrinsics
impl Send for Intrinsics
impl Sync for Intrinsics
impl Unpin for Intrinsics
impl UnwindSafe for Intrinsics
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> 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<T> SetParameter for T
impl<T> SetParameter 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§unsafe fn to_subset_unchecked(&self) -> SS
unsafe 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.