Struct PointWorldFrameWithSumReprojError

Source
pub struct PointWorldFrameWithSumReprojError<R: RealField + Copy> {
    pub point: PointWorldFrame<R>,
    pub cum_reproj_dist: R,
    pub mean_reproj_dist: R,
    pub reproj_dists: Vec<R>,
}
Expand description

A 3D world point with associated reprojection error statistics.

This structure extends PointWorldFrame with additional information about how well the reconstructed 3D point reprojects back to the original 2D observations in each camera. This is useful for quality assessment and outlier detection in 3D reconstruction.

§Reprojection Error

Reprojection error measures how far the reconstructed 3D point projects from the original 2D observations when projected back into each camera. Lower values indicate better reconstruction quality.

§Fields

  • point: The reconstructed 3D point in world coordinates
  • cum_reproj_dist: Sum of reprojection distances across all cameras
  • mean_reproj_dist: Average reprojection distance per camera
  • reproj_dists: Individual reprojection distance for each camera

§Example

use braid_mvg::{PointWorldFrame, PointWorldFrameWithSumReprojError};
use nalgebra::Point3;

let point = PointWorldFrame { coords: Point3::new(1.0, 2.0, 3.0) };
let errors = vec![0.5, 0.3, 0.8]; // reprojection errors for 3 cameras

let point_with_error = PointWorldFrameWithSumReprojError::new(point, errors);
println!("Mean reprojection error: {:.3}", point_with_error.mean_reproj_dist);

Fields§

§point: PointWorldFrame<R>

The reconstructed 3D point in world coordinates.

§cum_reproj_dist: R

Sum of reprojection distances from all cameras.

§mean_reproj_dist: R

Average reprojection distance per camera.

§reproj_dists: Vec<R>

Individual reprojection distances for each camera.

Implementations§

Source§

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

Source

pub fn new(point: PointWorldFrame<R>, reproj_dists: Vec<R>) -> Self

Create a new point with reprojection error statistics.

This constructor automatically computes the cumulative and mean reprojection errors from the individual camera errors.

§Arguments
  • point - The 3D point in world coordinates
  • reproj_dists - Vector of reprojection distances, one per camera
§Returns

A new instance with computed error statistics

§Example
use braid_mvg::{PointWorldFrame, PointWorldFrameWithSumReprojError};
use nalgebra::Point3;

let point = PointWorldFrame { coords: Point3::new(0.0, 0.0, 5.0) };
let errors = vec![0.1, 0.2, 0.15]; // errors from 3 cameras

let result = PointWorldFrameWithSumReprojError::new(point, errors);
assert!((result.mean_reproj_dist - 0.15f64).abs() < 1e-10);
assert!((result.cum_reproj_dist - 0.45f64).abs() < 1e-10);

Trait Implementations§

Source§

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

Source§

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

Returns a duplicate 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 PointWorldFrameWithSumReprojError<R>

Source§

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

Formats the value using the given formatter. Read more

Auto Trait Implementations§

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

Source§

fn az<Dst>(self) -> Dst
where T: Cast<Dst>,

Casts the value.
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<Src, Dst> CastFrom<Src> for Dst
where Src: Cast<Dst>,

Source§

fn cast_from(src: Src) -> Dst

Casts the value.
Source§

impl<T> CheckedAs for T

Source§

fn checked_as<Dst>(self) -> Option<Dst>
where T: CheckedCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> CheckedCastFrom<Src> for Dst
where Src: CheckedCast<Dst>,

Source§

fn checked_cast_from(src: Src) -> Option<Dst>

Casts the value.
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T> Instrument for T

Source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
Source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
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<Src, Dst> LosslessTryInto<Dst> for Src
where Dst: LosslessTryFrom<Src>,

Source§

fn lossless_try_into(self) -> Option<Dst>

Performs the conversion.
Source§

impl<Src, Dst> LossyInto<Dst> for Src
where Dst: LossyFrom<Src>,

Source§

fn lossy_into(self) -> Dst

Performs the conversion.
Source§

impl<T> OverflowingAs for T

Source§

fn overflowing_as<Dst>(self) -> (Dst, bool)
where T: OverflowingCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> OverflowingCastFrom<Src> for Dst
where Src: OverflowingCast<Dst>,

Source§

fn overflowing_cast_from(src: Src) -> (Dst, bool)

Casts the value.
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<T> SaturatingAs for T

Source§

fn saturating_as<Dst>(self) -> Dst
where T: SaturatingCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> SaturatingCastFrom<Src> for Dst
where Src: SaturatingCast<Dst>,

Source§

fn saturating_cast_from(src: Src) -> Dst

Casts the value.
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,

Source§

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

Source§

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

Source§

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

Source§

fn unwrapped_as<Dst>(self) -> Dst
where T: UnwrappedCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> UnwrappedCastFrom<Src> for Dst
where Src: UnwrappedCast<Dst>,

Source§

fn unwrapped_cast_from(src: Src) -> Dst

Casts the value.
Source§

impl<T> WithSubscriber for T

Source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

impl<T> WrappingAs for T

Source§

fn wrapping_as<Dst>(self) -> Dst
where T: WrappingCast<Dst>,

Casts the value.
Source§

impl<Src, Dst> WrappingCastFrom<Src> for Dst
where Src: WrappingCast<Dst>,

Source§

fn wrapping_cast_from(src: Src) -> Dst

Casts the value.
Source§

impl<T> Allocation for T
where T: RefUnwindSafe + Send + Sync,