pub struct MultiCameraSystem<R: RealField + Serialize + Copy> { /* private fields */ }Expand description
A calibrated multi-camera system for 3D computer vision applications.
This structure manages a collection of cameras with known intrinsic and extrinsic parameters, providing high-level operations for 3D reconstruction, triangulation, and geometric analysis. It’s the primary interface for multi-view geometry operations in the Braid system.
§Core Capabilities
- 3D Triangulation: Reconstruct 3D points from 2D observations across cameras
- Reprojection Analysis: Compute and analyze reprojection errors for quality assessment
- Geometric Validation: Verify camera calibration quality and detect issues
- Format Conversion: Import/export from various camera system formats (PyMVG, etc.)
§Mathematical Foundation
The system operates on the principle that multiple cameras observing the same 3D point provide redundant information that can be used to:
- Triangulate the 3D position via geometric intersection of viewing rays
- Validate the reconstruction by reprojecting back to all cameras
- Optimize camera parameters through bundle adjustment
§Camera Naming
Cameras are identified by string names within the system. This allows for flexible camera management and easy association of observations with specific cameras.
§Example
use braid_mvg::{Camera, MultiCameraSystem, PointWorldFrame, extrinsics, make_default_intrinsics, UndistortedPixel};
use std::collections::BTreeMap;
use nalgebra::{Point3, Point2};
// Create cameras
let camera1 = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
let camera2 = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
// Build multi-camera system
let mut cameras = BTreeMap::new();
cameras.insert("cam1".to_string(), camera1);
cameras.insert("cam2".to_string(), camera2);
let system = MultiCameraSystem::new(cameras);
// Create observations for triangulation as slice of tuples
let observations = vec![
("cam1".to_string(), UndistortedPixel { coords: Point2::new(320.0, 240.0) }),
("cam2".to_string(), UndistortedPixel { coords: Point2::new(320.0, 240.0) }),
];
// Use for 3D triangulation
if let Ok(point_3d) = system.find3d(&observations) {
println!("Reconstructed 3D point: {:?}", point_3d.coords);
}Implementations§
Source§impl<R> MultiCameraSystem<R>
impl<R> MultiCameraSystem<R>
Sourcepub fn from_pymvg_json<Rd: Read>(reader: Rd) -> Result<Self>
pub fn from_pymvg_json<Rd: Read>(reader: Rd) -> Result<Self>
Create a multi-camera system from PyMVG JSON format.
This constructor deserializes a multi-camera system from PyMVG JSON format, reading from the provided reader.
§Arguments
reader- Reader containing PyMVG JSON data
§Returns
A new MultiCameraSystem instance, or MvgError if parsing fails.
Source§impl<R: RealField + Default + Serialize + Copy> MultiCameraSystem<R>
impl<R: RealField + Default + Serialize + Copy> MultiCameraSystem<R>
Sourcepub fn new(cams_by_name: BTreeMap<String, Camera<R>>) -> Self
pub fn new(cams_by_name: BTreeMap<String, Camera<R>>) -> Self
Create a new multi-camera system from a collection of cameras.
§Arguments
cams_by_name- Map of camera names toCamerainstances
§Returns
A new MultiCameraSystem instance
Sourcepub fn comment(&self) -> Option<&String>
pub fn comment(&self) -> Option<&String>
Get an optional comment describing this camera system.
§Returns
Optional reference to the comment string
Sourcepub fn cams_by_name(&self) -> &BTreeMap<String, Camera<R>>
pub fn cams_by_name(&self) -> &BTreeMap<String, Camera<R>>
Get the collection of cameras in this system.
Sourcepub fn new_with_comment(
cams_by_name: BTreeMap<String, Camera<R>>,
comment: String,
) -> Self
pub fn new_with_comment( cams_by_name: BTreeMap<String, Camera<R>>, comment: String, ) -> Self
Create a new multi-camera system with an optional comment.
§Arguments
cams_by_name- Map of camera names toCamerainstancescomment- Descriptive comment for the camera system
§Returns
A new MultiCameraSystem instance
Sourcepub fn new_inner(
cams_by_name: BTreeMap<String, Camera<R>>,
comment: Option<String>,
) -> Self
pub fn new_inner( cams_by_name: BTreeMap<String, Camera<R>>, comment: Option<String>, ) -> Self
Internal constructor for creating a multi-camera system.
§Arguments
cams_by_name- Map of camera names toCamerainstancescomment- Optional descriptive comment
§Returns
A new MultiCameraSystem instance
Sourcepub fn cam_by_name(&self, name: &str) -> Option<&Camera<R>>
pub fn cam_by_name(&self, name: &str) -> Option<&Camera<R>>
Sourcepub fn from_pymvg(pymvg_system: &PymvgMultiCameraSystemV1<R>) -> Result<Self>
pub fn from_pymvg(pymvg_system: &PymvgMultiCameraSystemV1<R>) -> Result<Self>
Create a multi-camera system from a PyMVG data structure.
§Arguments
pymvg_system- PyMVG multi-camera system data structure
§Returns
A new MultiCameraSystem instance, or MvgError if conversion fails
Sourcepub fn to_pymvg(&self) -> Result<PymvgMultiCameraSystemV1<R>>
pub fn to_pymvg(&self) -> Result<PymvgMultiCameraSystemV1<R>>
Convert this multi-camera system to PyMVG format.
This method converts the camera system to PyMVG data structure format for interoperability with PyMVG library and JSON serialization.
§Returns
A PymvgMultiCameraSystemV1 structure, or MvgError if conversion fails
§Example
use braid_mvg::{MultiCameraSystem, Camera, extrinsics, make_default_intrinsics};
use std::collections::BTreeMap;
let mut cameras = BTreeMap::new();
cameras.insert("cam1".to_string(), Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?);
let system = MultiCameraSystem::new(cameras);
let pymvg_system = system.to_pymvg()?;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
Sourcepub fn align(&self, s: R, rot: Matrix3<R>, t: Vector3<R>) -> Result<Self>
pub fn align(&self, s: R, rot: Matrix3<R>, t: Vector3<R>) -> Result<Self>
Apply a similarity transformation to all cameras in the system.
This method applies the same similarity transformation (scale, rotation, translation) to all cameras in the multi-camera system. This is commonly used for:
- Coordinate system alignment between different camera systems
- Scale recovery in structure-from-motion pipelines
- Aligning reconstructed coordinates with ground truth
§Mathematical Details
The transformation applies: X' = s*R*X + t to all camera positions and orientations.
§Arguments
s- Uniform scale factor (must be positive)rot- 3×3 rotation matrix (must be orthogonal with determinant +1)t- 3×1 translation vector
§Returns
A new aligned MultiCameraSystem, or MvgError if transformation fails
§Errors
Returns an error if:
- The rotation matrix is invalid
- The scale factor is non-positive
- Any camera transformation fails
§Example
use braid_mvg::{MultiCameraSystem, Camera, extrinsics, make_default_intrinsics};
use nalgebra::{Matrix3, Vector3};
use std::collections::BTreeMap;
let mut cameras = BTreeMap::new();
cameras.insert("cam1".to_string(), Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?);
let system = MultiCameraSystem::new(cameras);
let scale = 2.0;
let rotation = Matrix3::identity();
let translation = Vector3::zeros();
let aligned_system = system.align(scale, rotation, translation)?;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>
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
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>,
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
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>,
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>
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>
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>
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>
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
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>,
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)
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>,
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
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>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
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
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.