Skip to main content

CameraController

Trait CameraController 

Source
pub trait CameraController: Controller {
    type Frame: Send + Sync;

    // Required methods
    fn capture_frame<'life0, 'async_trait>(
        &'life0 mut self,
    ) -> Pin<Box<dyn Future<Output = Result<Self::Frame, Self::Error>> + Send + 'async_trait>>
       where Self: 'async_trait,
             'life0: 'async_trait;
    fn intrinsics(&self) -> Option<CameraIntrinsics>;
    fn set_parameters<'life0, 'async_trait>(
        &'life0 mut self,
        params: CameraParameters,
    ) -> Pin<Box<dyn Future<Output = Result<(), Self::Error>> + Send + 'async_trait>>
       where Self: 'async_trait,
             'life0: 'async_trait;
    fn get_parameters<'life0, 'async_trait>(
        &'life0 self,
    ) -> Pin<Box<dyn Future<Output = Result<CameraParameters, Self::Error>> + Send + 'async_trait>>
       where Self: 'async_trait,
             'life0: 'async_trait;
    fn info(&self) -> CameraInfo;

    // Provided methods
    fn supports_depth(&self) -> bool { ... }
    fn supports_infrared(&self) -> bool { ... }
}
Expand description

Camera controller trait

Provides a unified interface for different camera types including:

  • RGB cameras (webcams, CSI cameras)
  • Depth cameras (RealSense, structured light)
  • RGBD cameras (RealSense D400 series)
  • Network cameras (RTSP streams)

Required Associated Types§

Source

type Frame: Send + Sync

Frame type produced by this camera

Required Methods§

Source

fn capture_frame<'life0, 'async_trait>( &'life0 mut self, ) -> Pin<Box<dyn Future<Output = Result<Self::Frame, Self::Error>> + Send + 'async_trait>>
where Self: 'async_trait, 'life0: 'async_trait,

Capture a single frame from the camera

This will block until a frame is available or an error occurs.

Source

fn intrinsics(&self) -> Option<CameraIntrinsics>

Get camera intrinsics if available

Returns calibration data including focal length, principal point, and distortion coefficients. May return None if not calibrated.

Source

fn set_parameters<'life0, 'async_trait>( &'life0 mut self, params: CameraParameters, ) -> Pin<Box<dyn Future<Output = Result<(), Self::Error>> + Send + 'async_trait>>
where Self: 'async_trait, 'life0: 'async_trait,

Set camera parameters

Adjust camera settings like exposure, gain, white balance, etc. Not all parameters may be supported by all cameras.

Source

fn get_parameters<'life0, 'async_trait>( &'life0 self, ) -> Pin<Box<dyn Future<Output = Result<CameraParameters, Self::Error>> + Send + 'async_trait>>
where Self: 'async_trait, 'life0: 'async_trait,

Get current camera parameters

Source

fn info(&self) -> CameraInfo

Get camera information

Provided Methods§

Source

fn supports_depth(&self) -> bool

Check if the camera supports depth

Source

fn supports_infrared(&self) -> bool

Check if the camera supports infrared

Implementors§