pub struct Camera<S, P, D, Sm, K>where
S: RealField + Copy,
P: ProjectionModel<S>,
D: DistortionModel<S>,
Sm: SensorModel<S>,
K: IntrinsicsModel<S>,{
pub proj: P,
pub dist: D,
pub sensor: Sm,
pub k: K,
/* private fields */
}Expand description
A composable camera model: projection -> distortion -> sensor -> intrinsics.
Fields§
§proj: PProjection model (e.g. pinhole).
dist: DDistortion model (e.g. Brown-Conrady).
sensor: SmSensor model (e.g. identity or tilted homography).
k: KIntrinsics model (K).
Implementations§
Source§impl<S, P, D, Sm, K> Camera<S, P, D, Sm, K>where
S: RealField + Copy,
P: ProjectionModel<S>,
D: DistortionModel<S>,
Sm: SensorModel<S>,
K: IntrinsicsModel<S>,
impl<S, P, D, Sm, K> Camera<S, P, D, Sm, K>where
S: RealField + Copy,
P: ProjectionModel<S>,
D: DistortionModel<S>,
Sm: SensorModel<S>,
K: IntrinsicsModel<S>,
Sourcepub fn new(proj: P, dist: D, sensor: Sm, k: K) -> Self
pub fn new(proj: P, dist: D, sensor: Sm, k: K) -> Self
Build a camera from its component models.
Sourcepub fn project_point_c(&self, p_c: &Vector3<S>) -> Option<Point2<S>>
pub fn project_point_c(&self, p_c: &Vector3<S>) -> Option<Point2<S>>
Project a 3D point in camera coordinates into pixel coordinates.
Returns None if the point is behind the camera or not projectable.
Sourcepub fn project_point(&self, p_c: &Point3<S>) -> Option<Point2<S>>
pub fn project_point(&self, p_c: &Point3<S>) -> Option<Point2<S>>
Project a 3D point in camera coordinates into pixel coordinates.
This is a convenience wrapper around project_point_c.
Sourcepub fn backproject_pixel(&self, px: &Point2<S>) -> Ray<S>
pub fn backproject_pixel(&self, px: &Point2<S>) -> Ray<S>
Backproject a pixel to a point on the z = 1 plane in camera coordinates.
Trait Implementations§
Source§impl<S, P, D, Sm, K> Clone for Camera<S, P, D, Sm, K>where
S: RealField + Copy + Clone,
P: ProjectionModel<S> + Clone,
D: DistortionModel<S> + Clone,
Sm: SensorModel<S> + Clone,
K: IntrinsicsModel<S> + Clone,
impl<S, P, D, Sm, K> Clone for Camera<S, P, D, Sm, K>where
S: RealField + Copy + Clone,
P: ProjectionModel<S> + Clone,
D: DistortionModel<S> + Clone,
Sm: SensorModel<S> + Clone,
K: IntrinsicsModel<S> + Clone,
Source§impl<S, P, D, Sm, K> Debug for Camera<S, P, D, Sm, K>where
S: RealField + Copy + Debug,
P: ProjectionModel<S> + Debug,
D: DistortionModel<S> + Debug,
Sm: SensorModel<S> + Debug,
K: IntrinsicsModel<S> + Debug,
impl<S, P, D, Sm, K> Debug for Camera<S, P, D, Sm, K>where
S: RealField + Copy + Debug,
P: ProjectionModel<S> + Debug,
D: DistortionModel<S> + Debug,
Sm: SensorModel<S> + Debug,
K: IntrinsicsModel<S> + Debug,
Source§impl<'de, S, P, D, Sm, K> Deserialize<'de> for Camera<S, P, D, Sm, K>where
S: RealField + Copy,
P: ProjectionModel<S> + Deserialize<'de>,
D: DistortionModel<S> + Deserialize<'de>,
Sm: SensorModel<S> + Deserialize<'de>,
K: IntrinsicsModel<S> + Deserialize<'de>,
impl<'de, S, P, D, Sm, K> Deserialize<'de> for Camera<S, P, D, Sm, K>where
S: RealField + Copy,
P: ProjectionModel<S> + Deserialize<'de>,
D: DistortionModel<S> + Deserialize<'de>,
Sm: SensorModel<S> + Deserialize<'de>,
K: IntrinsicsModel<S> + Deserialize<'de>,
Source§fn deserialize<__D>(__deserializer: __D) -> Result<Self, __D::Error>where
__D: Deserializer<'de>,
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<S, P, D, Sm, K> Serialize for Camera<S, P, D, Sm, K>where
S: RealField + Copy,
P: ProjectionModel<S> + Serialize,
D: DistortionModel<S> + Serialize,
Sm: SensorModel<S> + Serialize,
K: IntrinsicsModel<S> + Serialize,
impl<S, P, D, Sm, K> Serialize for Camera<S, P, D, Sm, K>where
S: RealField + Copy,
P: ProjectionModel<S> + Serialize,
D: DistortionModel<S> + Serialize,
Sm: SensorModel<S> + Serialize,
K: IntrinsicsModel<S> + Serialize,
Auto Trait Implementations§
impl<S, P, D, Sm, K> Freeze for Camera<S, P, D, Sm, K>
impl<S, P, D, Sm, K> RefUnwindSafe for Camera<S, P, D, Sm, K>
impl<S, P, D, Sm, K> Send for Camera<S, P, D, Sm, K>
impl<S, P, D, Sm, K> Sync for Camera<S, P, D, Sm, K>
impl<S, P, D, Sm, K> Unpin for Camera<S, P, D, Sm, K>
impl<S, P, D, Sm, K> UnsafeUnpin for Camera<S, P, D, Sm, K>
impl<S, P, D, Sm, K> UnwindSafe for Camera<S, P, D, Sm, K>
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
Mutably borrows from an owned value. Read more
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
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>
The inverse inclusion map: attempts to construct
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
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
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
fn from_subset(element: &SS) -> SP
The inclusion map: converts
self to the equivalent element of its superset.