Struct mvg::Camera

source ·
pub struct Camera<R: RealField + Copy> { /* private fields */ }

Implementations§

source§

impl<R: RealField + Copy> Camera<R>

source

pub fn new( width: usize, height: usize, extrinsics: ExtrinsicParameters<R>, intrinsics: RosOpenCvIntrinsics<R> ) -> Result<Self>

source

pub fn from_pmat( width: usize, height: usize, pmat: &OMatrix<R, U3, U4> ) -> Result<Self>

source

pub fn as_pmat(&self) -> Option<&OMatrix<R, U3, U4>>

convert, if possible, into a 3x4 matrix

source

pub fn linear_part_as_pmat(&self) -> &OMatrix<R, U3, U4>

source

pub fn linearize_to_cam_geom( &self ) -> Camera<R, IntrinsicParametersPerspective<R>>

Return a linearized copy of self.

The returned camera will not have distortion. In other words, the raw projected (“distorted”) pixels are identical with the “undistorted” variant. The camera model is a perfect linear pinhole.

source

pub fn align(&self, s: R, rot: Matrix3<R>, t: Vector3<R>) -> Result<Self>

source

pub fn flip(&self) -> Option<Camera<R>>

return a copy of this camera looking in the opposite direction

The returned camera has the same 3D->2D projection. (The 2D->3D projection results in a vector in the opposite direction.)

source

pub fn intrinsics(&self) -> &RosOpenCvIntrinsics<R>

source

pub fn extrinsics(&self) -> &ExtrinsicParameters<R>

source

pub fn to_pymvg(&self, name: &str) -> PymvgCamera<R>

source

pub fn width(&self) -> usize

source

pub fn height(&self) -> usize

source

pub fn project_3d_to_pixel( &self, pt3d: &PointWorldFrame<R> ) -> UndistortedPixel<R>

source

pub fn project_3d_to_distorted_pixel( &self, pt3d: &PointWorldFrame<R> ) -> DistortedPixel<R>

source

pub fn project_pixel_to_3d_with_dist( &self, pt2d: &UndistortedPixel<R>, dist: R ) -> PointWorldFrame<R>

source

pub fn project_distorted_pixel_to_3d_with_dist( &self, pt2d: &DistortedPixel<R>, dist: R ) -> PointWorldFrame<R>

Trait Implementations§

source§

impl<R: RealField + Copy> AsRef<Camera<R, RosOpenCvIntrinsics<R>>> for Camera<R>

source§

fn as_ref(&self) -> &Camera<R, RosOpenCvIntrinsics<R>>

Converts this type into a shared reference of the (usually inferred) input type.
source§

impl<R: Clone + RealField + Copy> Clone for Camera<R>

source§

fn clone(&self) -> Camera<R>

Returns a copy of the value. Read more
1.0.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl<R: Debug + RealField + Copy> Debug for Camera<R>

source§

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

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

impl<R: RealField + Copy> Default for Camera<R>

source§

fn default() -> Camera<R>

Returns the “default value” for a type. Read more
source§

impl<'de, R: RealField + Deserialize<'de> + Copy> Deserialize<'de> for Camera<R>

source§

fn deserialize<D>(deserializer: D) -> Result<Self, D::Error>
where D: Deserializer<'de>,

Deserialize this value from the given Serde deserializer. Read more
source§

impl<R: PartialEq + RealField + Copy> PartialEq for Camera<R>

source§

fn eq(&self, other: &Camera<R>) -> bool

This method tests for self and other values to be equal, and is used by ==.
1.0.0 · source§

fn ne(&self, other: &Rhs) -> bool

This method tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl<R: RealField + Serialize + Copy> Serialize for Camera<R>

source§

fn serialize<S>(&self, serializer: S) -> Result<S::Ok, S::Error>
where S: Serializer,

Serialize this value into the given Serde serializer. Read more
source§

impl<R: RealField + Copy> StructuralPartialEq for Camera<R>

Auto Trait Implementations§

§

impl<R> Freeze for Camera<R>
where R: Freeze,

§

impl<R> RefUnwindSafe for Camera<R>
where R: RefUnwindSafe,

§

impl<R> Send for Camera<R>

§

impl<R> Sync for Camera<R>

§

impl<R> Unpin for Camera<R>
where R: Unpin,

§

impl<R> UnwindSafe for Camera<R>
where R: UnwindSafe,

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> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

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> Same for T

§

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,

§

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>,

§

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>,

§

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<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,

source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,