pub struct ExtrinsicParameters<R: RealField> { /* private fields */ }
Expand description

Defines the pose of a camera in the world coordinate system.

Implementations§

source§

impl<R: RealField> ExtrinsicParameters<R>

source

pub fn from_rotation_and_camcenter( rotation: UnitQuaternion<R>, camcenter: Point3<R> ) -> Self

Create a new instance from a rotation and a camera center.

source

pub fn from_pose(pose: &Isometry3<R>) -> Self

Create a new instance from an nalgebra::Isometry3.

source

pub fn from_view( camcenter: &Vector3<R>, lookat: &Vector3<R>, up: &Unit<Vector3<R>> ) -> Self

Create a new instance from a camera center, a lookat vector, and an up vector.

source

pub fn camcenter(&self) -> &Point3<R>

Return the camera center

source

pub fn pose(&self) -> &Isometry3<R>

Return the camera pose

source

pub fn matrix(&self) -> &SMatrix<R, 3, 4>

Return the pose as a 3x4 matrix

source

pub fn rotation(&self) -> &Rotation3<R>

Return the rotation part of the pose

source

pub fn translation(&self) -> &Point3<R>

Return the translation part of the pose

source

pub fn forward(&self) -> Unit<Vector3<R>>

Return a unit vector aligned along our look (+Z) direction.

source

pub fn up(&self) -> Unit<Vector3<R>>

Return a unit vector aligned along our up (-Y) direction.

source

pub fn right(&self) -> Unit<Vector3<R>>

Return a unit vector aligned along our right (+X) direction.

source

pub fn camera_to_world<NPTS, InStorage>( &self, cam_coords: &Points<CameraFrame, R, NPTS, InStorage> ) -> Points<WorldFrame, R, NPTS, Owned<R, NPTS, U3>>where NPTS: Dim, InStorage: Storage<R, NPTS, U3>, DefaultAllocator: Allocator<R, NPTS, U3>,

Convert points in camera coordinates to world coordinates.

source

pub fn ray_camera_to_world<BType, NPTS, StorageCamera>( &self, camera: &RayBundle<CameraFrame, BType, R, NPTS, StorageCamera> ) -> RayBundle<WorldFrame, BType, R, NPTS, Owned<R, NPTS, U3>>where BType: Bundle<R>, NPTS: Dim, StorageCamera: Storage<R, NPTS, U3>, DefaultAllocator: Allocator<R, NPTS, U3>,

Convert rays in camera coordinates to world coordinates.

source

pub fn world_to_camera<NPTS, InStorage>( &self, world: &Points<WorldFrame, R, NPTS, InStorage> ) -> Points<CameraFrame, R, NPTS, Owned<R, NPTS, U3>>where NPTS: Dim, InStorage: Storage<R, NPTS, U3>, DefaultAllocator: Allocator<R, NPTS, U3>,

Convert points in world coordinates to camera coordinates.

Trait Implementations§

source§

impl<R: Clone + RealField> Clone for ExtrinsicParameters<R>

source§

fn clone(&self) -> ExtrinsicParameters<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: RealField> Debug for ExtrinsicParameters<R>

source§

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

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

impl<'de, R: RealField + Deserialize<'de>> Deserialize<'de> for ExtrinsicParameters<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> PartialEq<ExtrinsicParameters<R>> for ExtrinsicParameters<R>

source§

fn eq(&self, other: &ExtrinsicParameters<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> Serialize for ExtrinsicParameters<R>where R: Serialize + RealField,

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> StructuralPartialEq for ExtrinsicParameters<R>

Auto Trait Implementations§

Blanket Implementations§

source§

impl<T> Any for Twhere T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for Twhere T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for Twhere 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 Twhere 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> Same<T> for T

§

type Output = T

Should always be Self
§

impl<SS, SP> SupersetOf<SS> for SPwhere SS: SubsetOf<SP>,

§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
source§

impl<T> ToOwned for Twhere 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 Twhere 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 Twhere 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 Twhere T: for<'de> Deserialize<'de>,

source§

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