pub struct Camera<R: RealField> { /* private fields */ }Expand description
A calibrated camera with both intrinsic and extrinsic parameters.
This structure represents a complete camera model including:
- Intrinsic parameters: focal length, principal point, distortion coefficients
- Extrinsic parameters: position and orientation in 3D space
- Image dimensions: width and height in pixels
The camera follows the standard computer vision coordinate conventions:
- Camera frame: X→right, Y→down, Z→forward (optical axis)
- Image coordinates: origin at top-left, X→right, Y→down
§Mathematical Model
The camera implements the projective camera model:
s[u v 1]ᵀ = K[R|t][X Y Z 1]ᵀwhere:
(X,Y,Z)are 3D world coordinates(u,v)are 2D undistorted image coordinatesKis the intrinsic matrix[R|t]represents rotation and translation (extrinsics)sis a scaling factor
Lens distortion is supported via the
opencv-ros-camera crate.
The parameters for the intrinsic matrix (focal length, principal point, and skew) in addition to the distortion parameters together comprise the intrinsic parameters, or “intrinsics”.
§Example
use braid_mvg::{Camera, extrinsics, make_default_intrinsics};
// Create a camera with default parameters
let extrinsics = extrinsics::make_default_extrinsics::<f64>();
let intrinsics = make_default_intrinsics::<f64>();
let camera = Camera::new(640, 480, extrinsics, intrinsics).unwrap();
// Project a 3D point to 2D
use braid_mvg::PointWorldFrame;
use nalgebra::Point3;
let point_3d = PointWorldFrame { coords: Point3::new(0.0, 0.0, 5.0) };
let pixel = camera.project_3d_to_pixel(&point_3d);Implementations§
Source§impl<R: RealField + Copy> Camera<R>
impl<R: RealField + Copy> Camera<R>
Sourcepub fn rr_pinhole_archetype(&self) -> Result<Pinhole, MvgError>
Available on crate feature rerun-io only.
pub fn rr_pinhole_archetype(&self) -> Result<Pinhole, MvgError>
rerun-io only.Return a re_types::archetypes::Pinhole
The conversion will not succeed if the camera cannot be represented exactly in re_types.
Source§impl<R: RealField + Copy> Camera<R>
impl<R: RealField + Copy> Camera<R>
Sourcepub fn new(
width: usize,
height: usize,
extrinsics: ExtrinsicParameters<R>,
intrinsics: RosOpenCvIntrinsics<R>,
) -> Result<Self>
pub fn new( width: usize, height: usize, extrinsics: ExtrinsicParameters<R>, intrinsics: RosOpenCvIntrinsics<R>, ) -> Result<Self>
Create a new camera from intrinsic and extrinsic parameters.
This constructor creates a complete camera model by combining:
- Image dimensions (width, height)
- Extrinsic parameters (camera pose in world coordinates)
- Intrinsic parameters (focal length, principal point, distortion)
§Arguments
width- Image width in pixelsheight- Image height in pixelsextrinsics- Camera position and orientation in world coordinatesintrinsics- Camera intrinsic parameters including distortion model
§Returns
A new Camera instance, or MvgError if the parameters are invalid.
§Errors
Returns an error if:
- The projection matrix cannot be computed
- The camera parameters are mathematically inconsistent
- SVD decomposition fails during initialization
§Example
use braid_mvg::{Camera, extrinsics, make_default_intrinsics};
let extrinsics = extrinsics::make_default_extrinsics::<f64>();
let intrinsics = make_default_intrinsics::<f64>();
let camera = Camera::new(640, 480, extrinsics, intrinsics)?;Sourcepub fn new_from_cam_geom(
width: usize,
height: usize,
inner: Camera<R, RosOpenCvIntrinsics<R>>,
) -> Result<Self>
pub fn new_from_cam_geom( width: usize, height: usize, inner: Camera<R, RosOpenCvIntrinsics<R>>, ) -> Result<Self>
Create a new camera from a cam-geom Camera instance.
This constructor wraps an existing cam-geom Camera with additional image dimension information and caching for performance.
§Arguments
width- Image width in pixelsheight- Image height in pixelsinner- A pre-constructed cam-geom Camera instance
§Returns
A new Camera instance, or MvgError if the camera cannot be constructed.
§Example
use braid_mvg::{Camera, extrinsics, make_default_intrinsics};
use cam_geom;
let extrinsics = extrinsics::make_default_extrinsics::<f64>();
let intrinsics = make_default_intrinsics::<f64>();
let cam_geom_camera = cam_geom::Camera::new(intrinsics, extrinsics);
let camera = Camera::new_from_cam_geom(640, 480, cam_geom_camera)?;Sourcepub fn from_pmat(
width: usize,
height: usize,
pmat: &OMatrix<R, U3, U4>,
) -> Result<Self>
pub fn from_pmat( width: usize, height: usize, pmat: &OMatrix<R, U3, U4>, ) -> Result<Self>
Create a camera from a 3×4 projection matrix.
This method decomposes a camera projection matrix into intrinsic and extrinsic parameters using QR decomposition. It assumes no lens distortion (pinhole model).
§Mathematical Background
The projection matrix P has the form:
P = K[R|t]where K is the 3×3 intrinsic matrix and [R|t] is the 3×4 extrinsic matrix.
§Arguments
width- Image width in pixelsheight- Image height in pixelspmat- 3×4 projection matrix
§Returns
A new Camera instance with no distortion, or MvgError if decomposition fails.
§Errors
Returns an error if:
- The projection matrix is singular or ill-conditioned
- QR decomposition fails
- The resulting parameters are invalid
§Example
use braid_mvg::Camera;
use nalgebra::{OMatrix, U3, U4};
// Create a simple projection matrix
let pmat = OMatrix::<f64, U3, U4>::new(
1000.0, 0.0, 320.0, 100.0,
0.0, 1000.0, 240.0, 200.0,
0.0, 0.0, 1.0, 0.01
);
let camera = Camera::from_pmat(640, 480, &pmat)?;Sourcepub fn linear_part_as_pmat(&self) -> &OMatrix<R, U3, U4>
pub fn linear_part_as_pmat(&self) -> &OMatrix<R, U3, U4>
Get the linear projection matrix (3×4) for this camera.
This returns the cached projection matrix that represents a linearized version of the camera model (without lens distortion). The matrix has the form P = K[R|t] where K is the intrinsic matrix and [R|t] are the extrinsic parameters.
§Returns
Reference to the 3×4 projection matrix
§Example
use braid_mvg::{Camera, extrinsics, make_default_intrinsics};
let camera = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
let pmat = camera.linear_part_as_pmat();
println!("Projection matrix shape: {}×{}", pmat.nrows(), pmat.ncols());Sourcepub fn linearize_to_cam_geom(
&self,
) -> Camera<R, IntrinsicParametersPerspective<R>>
pub fn linearize_to_cam_geom( &self, ) -> Camera<R, IntrinsicParametersPerspective<R>>
Return a linearized copy of self.
The returned camera will not have distortion. In other words, the raw projected (“distorted”) pixels are identical with the “undistorted” variant. The camera model is a perfect linear pinhole.
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>
Transform this camera using a similarity transformation.
This method applies a similarity transformation (scale, rotation, translation) to align the camera coordinate system. This is commonly used in:
- Multi-camera system calibration
- Coordinate system alignment
- Scale recovery in structure-from-motion
§Mathematical Details
The transformation applies: X' = s*R*X + t where:
sis the uniform scale factorRis the 3×3 rotation matrixtis the 3×1 translation vectorXare the original 3D points
§Arguments
s- Uniform scale factor (positive)rot- 3×3 rotation matrix (must be orthogonal with det=1)t- 3×1 translation vector
§Returns
A new aligned Camera instance, or MvgError if transformation fails.
§Errors
Returns an error if:
- The rotation matrix is invalid (not orthogonal or det≠1)
- The scale factor is non-positive
- Camera reconstruction fails after transformation
§Example
use braid_mvg::{Camera, extrinsics, make_default_intrinsics};
use nalgebra::{Matrix3, Vector3};
let camera = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
let scale = 2.0;
let rotation = Matrix3::identity();
let translation = Vector3::new(1.0, 0.0, 0.0);
let aligned_camera = camera.align(scale, rotation, translation)?;Sourcepub fn flip(&self) -> Option<Camera<R>>
pub fn flip(&self) -> Option<Camera<R>>
return a copy of this camera looking in the opposite direction
The returned camera has the same 3D->2D projection. (The 2D->3D projection results in a vector in the opposite direction.)
Sourcepub fn intrinsics(&self) -> &RosOpenCvIntrinsics<R>
pub fn intrinsics(&self) -> &RosOpenCvIntrinsics<R>
Get the camera’s intrinsic parameters.
Sourcepub fn extrinsics(&self) -> &ExtrinsicParameters<R>
pub fn extrinsics(&self) -> &ExtrinsicParameters<R>
Get the camera’s extrinsic parameters.
Sourcepub fn to_pymvg(&self, name: &str) -> PymvgCamera<R>
pub fn to_pymvg(&self, name: &str) -> PymvgCamera<R>
Convert this camera to PyMVG format.
PyMVG is a Python library for multiple view geometry. This method converts the camera parameters to the PyMVG JSON schema format for interoperability.
§Arguments
name- Name to assign to the camera in the PyMVG format
§Returns
A PymvgCamera struct containing the camera parameters in PyMVG format
§Example
use braid_mvg::{Camera, extrinsics, make_default_intrinsics};
let camera = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
let pymvg_camera = camera.to_pymvg("camera1");Sourcepub fn project_3d_to_pixel(
&self,
pt3d: &PointWorldFrame<R>,
) -> UndistortedPixel<R>
pub fn project_3d_to_pixel( &self, pt3d: &PointWorldFrame<R>, ) -> UndistortedPixel<R>
Project a 3D world point to undistorted 2D image coordinates.
This method performs the core camera projection operation, transforming a 3D point in world coordinates to 2D pixel coordinates. The result represents the undistorted pixel coordinates (as if using a perfect pinhole camera model).
Sourcepub fn project_3d_to_distorted_pixel(
&self,
pt3d: &PointWorldFrame<R>,
) -> DistortedPixel<R>
pub fn project_3d_to_distorted_pixel( &self, pt3d: &PointWorldFrame<R>, ) -> DistortedPixel<R>
Project a 3D world point to distorted 2D image coordinates.
This method projects a 3D point to 2D image coordinates and then applies lens distortion to get the actual pixel coordinates as they would appear in the raw camera image.
§Arguments
pt3d- 3D point in world coordinates
§Returns
DistortedPixel containing the 2D image coordinates with distortion applied
§Example
use braid_mvg::{Camera, PointWorldFrame, extrinsics, make_default_intrinsics};
use nalgebra::Point3;
let camera = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
let point_3d = PointWorldFrame { coords: Point3::new(0.0, 0.0, 5.0) };
let distorted_pixel = camera.project_3d_to_distorted_pixel(&point_3d);Sourcepub fn project_pixel_to_3d_with_dist(
&self,
pt2d: &UndistortedPixel<R>,
dist: R,
) -> PointWorldFrame<R>
pub fn project_pixel_to_3d_with_dist( &self, pt2d: &UndistortedPixel<R>, dist: R, ) -> PointWorldFrame<R>
Back-project a 2D undistorted pixel to a 3D point at a given distance.
This method performs the inverse camera projection, taking a 2D pixel coordinate and a distance to compute the corresponding 3D world point. This is useful for depth-based reconstruction and ray casting.
§Arguments
pt2d- 2D pixel coordinates (undistorted)dist- Distance from camera center to the 3D point
§Returns
PointWorldFrame containing the 3D world coordinates
§Example
use braid_mvg::{Camera, UndistortedPixel, extrinsics, make_default_intrinsics};
use nalgebra::Point2;
let camera = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
let pixel = UndistortedPixel { coords: Point2::new(320.0, 240.0) };
let point_3d = camera.project_pixel_to_3d_with_dist(&pixel, 5.0);Sourcepub fn project_distorted_pixel_to_3d_with_dist(
&self,
pt2d: &DistortedPixel<R>,
dist: R,
) -> PointWorldFrame<R>
pub fn project_distorted_pixel_to_3d_with_dist( &self, pt2d: &DistortedPixel<R>, dist: R, ) -> PointWorldFrame<R>
Back-project a 2D distorted pixel to a 3D point at a given distance.
This method first removes lens distortion from the pixel coordinates, then back-projects to 3D space at the specified distance from the camera.
§Arguments
pt2d- 2D pixel coordinates (with distortion)dist- Distance from camera center to the 3D point
§Returns
PointWorldFrame containing the 3D world coordinates
§Example
use braid_mvg::{Camera, DistortedPixel, extrinsics, make_default_intrinsics};
use nalgebra::Point2;
let camera = Camera::new(640, 480,
extrinsics::make_default_extrinsics::<f64>(),
make_default_intrinsics::<f64>())?;
let pixel = DistortedPixel { coords: Point2::new(320.0, 240.0) };
let point_3d = camera.project_distorted_pixel_to_3d_with_dist(&pixel, 5.0);Trait Implementations§
Source§impl<R: RealField + Copy> AsRef<Camera<R, RosOpenCvIntrinsics<R>>> for Camera<R>
impl<R: RealField + Copy> AsRef<Camera<R, RosOpenCvIntrinsics<R>>> for Camera<R>
Source§fn as_ref(&self) -> &Camera<R, RosOpenCvIntrinsics<R>>
fn as_ref(&self) -> &Camera<R, RosOpenCvIntrinsics<R>>
Source§impl<'de, R: RealField + Deserialize<'de> + Copy> Deserialize<'de> for Camera<R>
impl<'de, R: RealField + Deserialize<'de> + Copy> Deserialize<'de> for Camera<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>,
impl<R: RealField> StructuralPartialEq for Camera<R>
Auto Trait Implementations§
impl<R> Freeze for Camera<R>where
R: Freeze,
impl<R> RefUnwindSafe for Camera<R>where
R: RefUnwindSafe,
impl<R> Send for Camera<R>
impl<R> Sync for Camera<R>
impl<R> Unpin for Camera<R>where
R: Unpin,
impl<R> UnwindSafe for Camera<R>where
R: UnwindSafe,
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.