Struct MultiCameraSystem

Source
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:

  1. Triangulate the 3D position via geometric intersection of viewing rays
  2. Validate the reconstruction by reprojecting back to all cameras
  3. 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>

Source

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

Export the camera system to PyMVG format via a writer.

This method serializes the multi-camera system to PyMVG JSON format, writing the result to the provided writer.

§Arguments
  • writer - Writer to output the PyMVG JSON data
§Returns

Ok(()) on success, or MvgError if serialization fails.

Source

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>

Source

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 to Camera instances
§Returns

A new MultiCameraSystem instance

Source

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

Get an optional comment describing this camera system.

§Returns

Optional reference to the comment string

Source

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

Get the collection of cameras in this system.

Source

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 to Camera instances
  • comment - Descriptive comment for the camera system
§Returns

A new MultiCameraSystem instance

Source

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 to Camera instances
  • comment - Optional descriptive comment
§Returns

A new MultiCameraSystem instance

Source

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

Get a camera by name.

§Arguments
  • name - Name of the camera to retrieve
§Returns

Optional reference to the Camera, or None if not found

Source

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

Source

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()?;
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>

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>

Source§

fn clone(&self) -> MultiCameraSystem<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 + 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

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

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

Source§

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

Source§

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