Struct mvg::MultiCameraSystem
source · pub struct MultiCameraSystem<R: RealField + Serialize + Copy> { /* private fields */ }
Implementations§
source§impl<R> MultiCameraSystem<R>
impl<R> MultiCameraSystem<R>
pub fn to_pymvg_writer<W: Write>(&self, writer: &mut W) -> Result<()>
pub fn from_pymvg_json<Rd: Read>(reader: Rd) -> Result<Self>
source§impl<R: RealField + Default + Serialize + Copy> MultiCameraSystem<R>
impl<R: RealField + Default + Serialize + Copy> MultiCameraSystem<R>
pub fn new(cams_by_name: BTreeMap<String, Camera<R>>) -> Self
pub fn comment(&self) -> Option<&String>
pub fn cams_by_name(&self) -> &BTreeMap<String, Camera<R>>
pub fn new_with_comment( cams_by_name: BTreeMap<String, Camera<R>>, comment: String ) -> Self
pub fn new_inner( cams_by_name: BTreeMap<String, Camera<R>>, comment: Option<String> ) -> Self
pub fn cams(&self) -> &BTreeMap<String, Camera<R>>
pub fn cam_by_name(&self, name: &str) -> Option<&Camera<R>>
pub fn from_pymvg(pymvg_system: &PymvgMultiCameraSystemV1<R>) -> Result<Self>
pub fn to_pymvg(&self) -> Result<PymvgMultiCameraSystemV1<R>>
sourcepub fn get_reprojection_undistorted_dists(
&self,
points: &[(String, UndistortedPixel<R>)],
this_3d_pt: &PointWorldFrame<R>
) -> Result<Vec<R>>
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.
sourcepub fn find3d_and_cum_reproj_dist(
&self,
points: &[(String, UndistortedPixel<R>)]
) -> Result<PointWorldFrameWithSumReprojError<R>>
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
sourcepub fn find3d(
&self,
points: &[(String, UndistortedPixel<R>)]
) -> Result<PointWorldFrame<R>>
pub fn find3d( &self, points: &[(String, UndistortedPixel<R>)] ) -> Result<PointWorldFrame<R>>
Find 3D coordinate using pixel coordinates from cameras
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>
impl<R: Clone + RealField + Serialize + Copy> Clone for MultiCameraSystem<R>
source§fn clone(&self) -> MultiCameraSystem<R>
fn clone(&self) -> MultiCameraSystem<R>
Returns a copy of the value. Read more
1.0.0 · source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
Performs copy-assignment from
source
. Read moresource§impl<'de, R> Deserialize<'de> for MultiCameraSystem<R>
impl<'de, R> Deserialize<'de> for MultiCameraSystem<R>
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<R: PartialEq + RealField + Serialize + Copy> PartialEq for MultiCameraSystem<R>
impl<R: PartialEq + RealField + Serialize + Copy> PartialEq for MultiCameraSystem<R>
source§fn eq(&self, other: &MultiCameraSystem<R>) -> bool
fn eq(&self, other: &MultiCameraSystem<R>) -> bool
This method tests for
self
and other
values to be equal, and is used
by ==
.source§impl<R> Serialize for MultiCameraSystem<R>
impl<R> Serialize for MultiCameraSystem<R>
impl<R: RealField + Serialize + Copy> StructuralPartialEq for MultiCameraSystem<R>
Auto Trait Implementations§
impl<R> Freeze for MultiCameraSystem<R>
impl<R> RefUnwindSafe for MultiCameraSystem<R>where
R: RefUnwindSafe,
impl<R> Send for MultiCameraSystem<R>
impl<R> Sync for MultiCameraSystem<R>
impl<R> Unpin for MultiCameraSystem<R>
impl<R> UnwindSafe for MultiCameraSystem<R>where
R: RefUnwindSafe,
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> 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<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.