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§
Required Methods§
Sourcefn 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 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.
Sourcefn intrinsics(&self) -> Option<CameraIntrinsics>
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.
Sourcefn 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 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.
Sourcefn 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 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
Sourcefn info(&self) -> CameraInfo
fn info(&self) -> CameraInfo
Get camera information
Provided Methods§
Sourcefn supports_depth(&self) -> bool
fn supports_depth(&self) -> bool
Check if the camera supports depth
Sourcefn supports_infrared(&self) -> bool
fn supports_infrared(&self) -> bool
Check if the camera supports infrared