Struct cam_geom::Camera

source ·
pub struct Camera<R, I>where
    I: IntrinsicParameters<R>,
    R: RealField,{ /* private fields */ }
Expand description

A camera model that can convert world coordinates into pixel coordinates.

Examples

Creates a new perspective camera:

use cam_geom::*;
use nalgebra::*;

// perepective parameters - focal length of 100, no skew, pixel center at (640,480)
let intrinsics = IntrinsicParametersPerspective::from(PerspectiveParams {
    fx: 100.0,
    fy: 100.0,
    skew: 0.0,
    cx: 640.0,
    cy: 480.0,
});

// Set extrinsic parameters - camera at (10,0,10), looing at (0,0,0), up (0,0,1)
let camcenter = Vector3::new(10.0, 0.0, 10.0);
let lookat = Vector3::new(0.0, 0.0, 0.0);
let up = Unit::new_normalize(Vector3::new(0.0, 0.0, 1.0));
let pose = ExtrinsicParameters::from_view(&camcenter, &lookat, &up);

// Create camera with both intrinsic and extrinsic parameters.
let cam = Camera::new(intrinsics, pose);

Creates a new orthographic camera:

use cam_geom::*;
use nalgebra::*;

// orthographic parameters - scale of 100, pixel center at (640,480)
let intrinsics = IntrinsicParametersOrthographic::from(OrthographicParams {
    sx: 100.0,
    sy: 100.0,
    cx: 640.0,
    cy: 480.0,
});

// Set extrinsic parameters - camera at (10,0,10), looing at (0,0,0), up (0,0,1)
let camcenter = Vector3::new(10.0, 0.0, 10.0);
let lookat = Vector3::new(0.0, 0.0, 0.0);
let up = Unit::new_normalize(Vector3::new(0.0, 0.0, 1.0));
let pose = ExtrinsicParameters::from_view(&camcenter, &lookat, &up);

// Create camera with both intrinsic and extrinsic parameters.
let cam = Camera::new(intrinsics, pose);

Implementations§

source§

impl<R, I> Camera<R, I>where I: IntrinsicParameters<R>, R: RealField,

source

pub fn new(intrinsics: I, extrinsics: ExtrinsicParameters<R>) -> Self

Create a new camera from intrinsic and extrinsic parameters.

Arguments

Intrinsic parameters and extrinsic parameters

source

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

Return a reference to the extrinsic parameters.

source

pub fn intrinsics(&self) -> &I

Return a reference to the intrinsic parameters.

source

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

take 3D coordinates in world frame and convert to pixel coordinates

source

pub fn pixel_to_world<IN, NPTS>( &self, pixels: &Pixels<R, NPTS, IN> ) -> RayBundle<WorldFrame, I::BundleType, R, NPTS, Owned<R, NPTS, U3>>where I::BundleType: Bundle<R>, IN: Storage<R, NPTS, U2>, NPTS: Dim, DefaultAllocator: Allocator<R, U1, U2> + Allocator<R, NPTS, U2> + Allocator<R, NPTS, U3>,

take pixel coordinates and project to 3D in world frame

output arguments: camera - camera frame coordinate rays world - world frame coordinate rays

Note that the camera frame coordinates are returned as they must be computed anyway, so this additional data is “free”.

source§

impl<R: RealField> Camera<R, IntrinsicParametersPerspective<R>>

source

pub fn from_perspective_matrix<S>( pmat: &Matrix<R, U3, U4, S> ) -> Result<Self, Error>where S: Storage<R, U3, U4> + Clone,

Create a Camera from a 3x4 perspective projection matrix.

source

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

Create a 3x4 perspective projection matrix modeling this camera.

Trait Implementations§

source§

impl<R, I> Clone for Camera<R, I>where I: IntrinsicParameters<R> + Clone, R: RealField + Clone,

source§

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

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, I> Debug for Camera<R, I>where I: IntrinsicParameters<R> + Debug, R: RealField + Debug,

source§

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

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

impl<'de, R, I> Deserialize<'de> for Camera<R, I>where I: IntrinsicParameters<R> + Deserialize<'de>, R: RealField + Deserialize<'de>,

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, I> PartialEq<Camera<R, I>> for Camera<R, I>where I: IntrinsicParameters<R> + PartialEq, R: RealField + PartialEq,

source§

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

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, I> StructuralPartialEq for Camera<R, I>where I: IntrinsicParameters<R>, R: RealField,

Auto Trait Implementations§

§

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

§

impl<R, I> Send for Camera<R, I>where I: Send,

§

impl<R, I> Sync for Camera<R, I>where I: Sync,

§

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

§

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

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,