pub struct WorldCoordAndUndistorted2D<R: RealField + Copy> { /* private fields */ }Expand description
A combined data structure containing a 3D world point and its 2D camera observations.
This structure packages together a 3D point (possibly with reprojection errors) and the corresponding 2D undistorted pixel observations from each camera. This is useful for algorithms that need to work with both the 3D structure and the 2D observations simultaneously.
§Use Cases
- Bundle adjustment optimization
- Outlier detection and filtering
- Tracking and correspondence validation
- Quality assessment of triangulation results
§Example
use braid_mvg::{WorldCoordAndUndistorted2D, PointWorldFrame,
PointWorldFrameMaybeWithSumReprojError, UndistortedPixel};
use nalgebra::{Point2, Point3};
let point = PointWorldFrame { coords: Point3::new(1.0, 2.0, 3.0) };
let maybe_point = PointWorldFrameMaybeWithSumReprojError::Point(point);
let observations = vec![
("cam1".to_string(), UndistortedPixel { coords: Point2::new(320.0, 240.0) }),
("cam2".to_string(), UndistortedPixel { coords: Point2::new(340.0, 250.0) }),
];
let combined = WorldCoordAndUndistorted2D::new(maybe_point, observations);Implementations§
Source§impl<R: RealField + Copy> WorldCoordAndUndistorted2D<R>
impl<R: RealField + Copy> WorldCoordAndUndistorted2D<R>
Sourcepub fn new(
wc: PointWorldFrameMaybeWithSumReprojError<R>,
upoints: Vec<(String, UndistortedPixel<R>)>,
) -> Self
pub fn new( wc: PointWorldFrameMaybeWithSumReprojError<R>, upoints: Vec<(String, UndistortedPixel<R>)>, ) -> Self
Sourcepub fn point(self) -> PointWorldFrame<R>
pub fn point(self) -> PointWorldFrame<R>
Sourcepub fn wc_and_upoints(
self,
) -> (PointWorldFrameMaybeWithSumReprojError<R>, Vec<(String, UndistortedPixel<R>)>)
pub fn wc_and_upoints( self, ) -> (PointWorldFrameMaybeWithSumReprojError<R>, Vec<(String, UndistortedPixel<R>)>)
Decompose into the constituent 3D and 2D components.
§Returns
A tuple containing:
- The 3D world coordinates (possibly with error information)
- The vector of 2D observations from each camera
Trait Implementations§
Auto Trait Implementations§
impl<R> Freeze for WorldCoordAndUndistorted2D<R>where
R: Freeze,
impl<R> RefUnwindSafe for WorldCoordAndUndistorted2D<R>where
R: RefUnwindSafe,
impl<R> Send for WorldCoordAndUndistorted2D<R>
impl<R> Sync for WorldCoordAndUndistorted2D<R>
impl<R> Unpin for WorldCoordAndUndistorted2D<R>where
R: Unpin,
impl<R> UnwindSafe for WorldCoordAndUndistorted2D<R>where
R: UnwindSafe,
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> CheckedAs for T
impl<T> CheckedAs for T
Source§fn checked_as<Dst>(self) -> Option<Dst>where
T: CheckedCast<Dst>,
fn checked_as<Dst>(self) -> Option<Dst>where
T: CheckedCast<Dst>,
Casts the value.
Source§impl<Src, Dst> CheckedCastFrom<Src> for Dstwhere
Src: CheckedCast<Dst>,
impl<Src, Dst> CheckedCastFrom<Src> for Dstwhere
Src: CheckedCast<Dst>,
Source§fn checked_cast_from(src: Src) -> Option<Dst>
fn checked_cast_from(src: Src) -> Option<Dst>
Casts the value.
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<T> Instrument for T
impl<T> Instrument for T
Source§fn instrument(self, span: Span) -> Instrumented<Self>
fn instrument(self, span: Span) -> Instrumented<Self>
Source§fn in_current_span(self) -> Instrumented<Self>
fn in_current_span(self) -> Instrumented<Self>
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>
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 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>
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 moreSource§impl<Src, Dst> LosslessTryInto<Dst> for Srcwhere
Dst: LosslessTryFrom<Src>,
impl<Src, Dst> LosslessTryInto<Dst> for Srcwhere
Dst: LosslessTryFrom<Src>,
Source§fn lossless_try_into(self) -> Option<Dst>
fn lossless_try_into(self) -> Option<Dst>
Performs the conversion.
Source§impl<Src, Dst> LossyInto<Dst> for Srcwhere
Dst: LossyFrom<Src>,
impl<Src, Dst> LossyInto<Dst> for Srcwhere
Dst: LossyFrom<Src>,
Source§fn lossy_into(self) -> Dst
fn lossy_into(self) -> Dst
Performs the conversion.
Source§impl<T> OverflowingAs for T
impl<T> OverflowingAs for T
Source§fn overflowing_as<Dst>(self) -> (Dst, bool)where
T: OverflowingCast<Dst>,
fn overflowing_as<Dst>(self) -> (Dst, bool)where
T: OverflowingCast<Dst>,
Casts the value.
Source§impl<Src, Dst> OverflowingCastFrom<Src> for Dstwhere
Src: OverflowingCast<Dst>,
impl<Src, Dst> OverflowingCastFrom<Src> for Dstwhere
Src: OverflowingCast<Dst>,
Source§fn overflowing_cast_from(src: Src) -> (Dst, bool)
fn overflowing_cast_from(src: Src) -> (Dst, bool)
Casts the value.
Source§impl<T> SaturatingAs for T
impl<T> SaturatingAs for T
Source§fn saturating_as<Dst>(self) -> Dstwhere
T: SaturatingCast<Dst>,
fn saturating_as<Dst>(self) -> Dstwhere
T: SaturatingCast<Dst>,
Casts the value.
Source§impl<Src, Dst> SaturatingCastFrom<Src> for Dstwhere
Src: SaturatingCast<Dst>,
impl<Src, Dst> SaturatingCastFrom<Src> for Dstwhere
Src: SaturatingCast<Dst>,
Source§fn saturating_cast_from(src: Src) -> Dst
fn saturating_cast_from(src: Src) -> Dst
Casts the value.
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.Source§impl<T> UnwrappedAs for T
impl<T> UnwrappedAs for T
Source§fn unwrapped_as<Dst>(self) -> Dstwhere
T: UnwrappedCast<Dst>,
fn unwrapped_as<Dst>(self) -> Dstwhere
T: UnwrappedCast<Dst>,
Casts the value.
Source§impl<Src, Dst> UnwrappedCastFrom<Src> for Dstwhere
Src: UnwrappedCast<Dst>,
impl<Src, Dst> UnwrappedCastFrom<Src> for Dstwhere
Src: UnwrappedCast<Dst>,
Source§fn unwrapped_cast_from(src: Src) -> Dst
fn unwrapped_cast_from(src: Src) -> Dst
Casts the value.
Source§impl<T> WithSubscriber for T
impl<T> WithSubscriber for T
Source§fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
Source§fn with_current_subscriber(self) -> WithDispatch<Self>
fn with_current_subscriber(self) -> WithDispatch<Self>
Source§impl<T> WrappingAs for T
impl<T> WrappingAs for T
Source§fn wrapping_as<Dst>(self) -> Dstwhere
T: WrappingCast<Dst>,
fn wrapping_as<Dst>(self) -> Dstwhere
T: WrappingCast<Dst>,
Casts the value.
Source§impl<Src, Dst> WrappingCastFrom<Src> for Dstwhere
Src: WrappingCast<Dst>,
impl<Src, Dst> WrappingCastFrom<Src> for Dstwhere
Src: WrappingCast<Dst>,
Source§fn wrapping_cast_from(src: Src) -> Dst
fn wrapping_cast_from(src: Src) -> Dst
Casts the value.