Struct flydra_mvg::FlydraMultiCameraSystem

source ·
pub struct FlydraMultiCameraSystem<R: RealField + Copy + Serialize> { /* private fields */ }

Implementations§

source§

impl<R: RealField + Copy + Default + Serialize> FlydraMultiCameraSystem<R>

source

pub fn from_system(system: MultiCameraSystem<R>, water: Option<R>) -> Self

source

pub fn has_refractive_boundary(&self) -> bool

source

pub fn to_system(self) -> MultiCameraSystem<R>

source

pub fn system(&self) -> &MultiCameraSystem<R>

source

pub fn new(cams_by_name: BTreeMap<String, Camera<R>>, water: Option<R>) -> Self

source

pub fn len(&self) -> usize

source

pub fn is_empty(&self) -> bool

source

pub fn cam_by_name(&self, name: &str) -> Option<MultiCamera<R>>

source

pub fn cam_names(&self) -> CamNameIter<'_, R>

source

pub fn cameras(&self) -> MultiCameraIter<'_, '_, R>

source

pub fn find3d_and_cum_reproj_dist_distorted( &self, points: &[(String, DistortedPixel<R>)] ) -> Result<PointWorldFrameWithSumReprojError<R>>

source

pub fn find3d( &self, points: &[(String, UndistortedPixel<R>)] ) -> Result<PointWorldFrameMaybeWithSumReprojError<R>>

Find 3D coordinate using pixel coordinates from cameras

If the system has water, two evaluations are done: one for the case of the 3D point being under water, the other for the case of the 3D point being in air. The evaluation with the lowest mean reprojection error is selected.

source

pub fn find3d_distorted( &self, points: &[(String, DistortedPixel<R>)] ) -> Result<WorldCoordAndUndistorted2D<R>>

source

pub fn get_reprojection_undistorted_dists( &self, points: &[(String, UndistortedPixel<R>)], this_3d_pt: &PointWorldFrame<R> ) -> Result<Vec<R>>

Find reprojection error of 3D coordinate into pixel coordinates

source

pub fn from_flydra_reconstructor(recon: &FlydraReconstructor<R>) -> Result<Self>

source

pub fn to_flydra_reconstructor(&self) -> Result<FlydraReconstructor<R>>

source§

impl<R> FlydraMultiCameraSystem<R>

source

pub fn from_flydra_xml<Rd: Read>(reader: Rd) -> Result<Self>

source

pub fn to_flydra_xml<W: Write>(&self, writer: W) -> Result<()>

source

pub fn from_path<P>(cal_fname: P) -> Result<Self>
where P: AsRef<Path>,

Read a calibration from a path.

Trait Implementations§

source§

impl<R: Clone + RealField + Copy + Serialize> Clone for FlydraMultiCameraSystem<R>

source§

fn clone(&self) -> FlydraMultiCameraSystem<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: Debug + RealField + Copy + Serialize> Debug for FlydraMultiCameraSystem<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> 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<T> Downcast for T
where T: Any,

source§

fn into_any(self: Box<T>) -> Box<dyn Any>

Convert Box<dyn Trait> (where Trait: Downcast) to Box<dyn Any>. Box<dyn Any> can then be further downcast into Box<ConcreteType> where ConcreteType implements Trait.
source§

fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>

Convert Rc<Trait> (where Trait: Downcast) to Rc<Any>. Rc<Any> can then be further downcast into Rc<ConcreteType> where ConcreteType implements Trait.
source§

fn as_any(&self) -> &(dyn Any + 'static)

Convert &Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &Any’s vtable from &Trait’s.
source§

fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)

Convert &mut Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &mut Any’s vtable from &mut Trait’s.
source§

impl<T> DowncastSync for T
where T: Any + Send + Sync,

source§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Send + Sync>

Convert Arc<Trait> (where Trait: Downcast) to Arc<Any>. Arc<Any> can then be further downcast into Arc<ConcreteType> where ConcreteType implements Trait.
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

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

§

type Output = T

Should always be Self
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,

§

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

§

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

§

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.