Struct mvg::MultiCameraSystem

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

Implementations§

source§

impl<R> MultiCameraSystem<R>

source

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

source

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

source§

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

source

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

source

pub fn comment(&self) -> Option<&String>

source

pub fn cams_by_name(&self) -> &BTreeMap<String, Camera<R>>

source

pub fn new_with_comment( cams_by_name: BTreeMap<String, Camera<R>>, comment: String ) -> Self

source

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

source

pub fn cams(&self) -> &BTreeMap<String, Camera<R>>

source

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

source

pub fn from_pymvg(pymvg_system: &PymvgMultiCameraSystemV1<R>) -> Result<Self>

source

pub fn to_pymvg(&self) -> Result<PymvgMultiCameraSystemV1<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.

Note that this returns the reprojection distance of the undistorted pixels.

source

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

Find 3D coordinate and cumulative reprojection distance using pixel coordinates from cameras

source

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

Find 3D coordinate using pixel coordinates from cameras

source

pub fn align(&self, s: R, rot: Matrix3<R>, t: Vector3<R>) -> Result<Self>

Trait Implementations§

source§

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

source§

fn clone(&self) -> MultiCameraSystem<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 + Serialize + Copy> Debug for MultiCameraSystem<R>

source§

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

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

impl<'de, R> Deserialize<'de> for MultiCameraSystem<R>
where R: Deserialize<'de> + RealField + Serialize + Copy,

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: PartialEq + RealField + Serialize + Copy> PartialEq for MultiCameraSystem<R>

source§

fn eq(&self, other: &MultiCameraSystem<R>) -> 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> Serialize for MultiCameraSystem<R>

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: RealField + Serialize + Copy> StructuralPartialEq for MultiCameraSystem<R>

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> 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.
source§

impl<T> DeserializeOwned for T
where T: for<'de> Deserialize<'de>,

source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,