Trait mav_sdk::grpc::camera::camera_service_server::CameraService [−][src]
pub trait CameraService: Send + Sync + 'static {
type SubscribeModeStream: Stream<Item = Result<ModeResponse, Status>> + Send + Sync + 'static;
type SubscribeInformationStream: Stream<Item = Result<InformationResponse, Status>> + Send + Sync + 'static;
type SubscribeVideoStreamInfoStream: Stream<Item = Result<VideoStreamInfoResponse, Status>> + Send + Sync + 'static;
type SubscribeCaptureInfoStream: Stream<Item = Result<CaptureInfoResponse, Status>> + Send + Sync + 'static;
type SubscribeStatusStream: Stream<Item = Result<StatusResponse, Status>> + Send + Sync + 'static;
type SubscribeCurrentSettingsStream: Stream<Item = Result<CurrentSettingsResponse, Status>> + Send + Sync + 'static;
type SubscribePossibleSettingOptionsStream: Stream<Item = Result<PossibleSettingOptionsResponse, Status>> + Send + Sync + 'static;
Show 18 methods
fn take_photo<'life0, 'async_trait>(
&'life0 self,
request: Request<TakePhotoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<TakePhotoResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn start_photo_interval<'life0, 'async_trait>(
&'life0 self,
request: Request<StartPhotoIntervalRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartPhotoIntervalResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn stop_photo_interval<'life0, 'async_trait>(
&'life0 self,
request: Request<StopPhotoIntervalRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopPhotoIntervalResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn start_video<'life0, 'async_trait>(
&'life0 self,
request: Request<StartVideoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartVideoResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn stop_video<'life0, 'async_trait>(
&'life0 self,
request: Request<StopVideoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopVideoResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn start_video_streaming<'life0, 'async_trait>(
&'life0 self,
request: Request<StartVideoStreamingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartVideoStreamingResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn stop_video_streaming<'life0, 'async_trait>(
&'life0 self,
request: Request<StopVideoStreamingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopVideoStreamingResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn set_mode<'life0, 'async_trait>(
&'life0 self,
request: Request<SetModeRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<SetModeResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn subscribe_mode<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeModeRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeModeStream>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn subscribe_information<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeInformationRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeInformationStream>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn subscribe_video_stream_info<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeVideoStreamInfoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeVideoStreamInfoStream>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn subscribe_capture_info<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeCaptureInfoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeCaptureInfoStream>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn subscribe_status<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeStatusRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeStatusStream>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn subscribe_current_settings<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeCurrentSettingsRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeCurrentSettingsStream>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn subscribe_possible_setting_options<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribePossibleSettingOptionsRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribePossibleSettingOptionsStream>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn set_setting<'life0, 'async_trait>(
&'life0 self,
request: Request<SetSettingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<SetSettingResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn get_setting<'life0, 'async_trait>(
&'life0 self,
request: Request<GetSettingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<GetSettingResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
fn format_storage<'life0, 'async_trait>(
&'life0 self,
request: Request<FormatStorageRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<FormatStorageResponse>, Status>> + Send + 'async_trait>>
where
'life0: 'async_trait,
Self: 'async_trait;
}
Expand description
Generated trait containing gRPC methods that should be implemented for use with CameraServiceServer.
Associated Types
type SubscribeModeStream: Stream<Item = Result<ModeResponse, Status>> + Send + Sync + 'static
type SubscribeModeStream: Stream<Item = Result<ModeResponse, Status>> + Send + Sync + 'static
Server streaming response type for the SubscribeMode method.
type SubscribeInformationStream: Stream<Item = Result<InformationResponse, Status>> + Send + Sync + 'static
type SubscribeInformationStream: Stream<Item = Result<InformationResponse, Status>> + Send + Sync + 'static
Server streaming response type for the SubscribeInformation method.
type SubscribeVideoStreamInfoStream: Stream<Item = Result<VideoStreamInfoResponse, Status>> + Send + Sync + 'static
type SubscribeVideoStreamInfoStream: Stream<Item = Result<VideoStreamInfoResponse, Status>> + Send + Sync + 'static
Server streaming response type for the SubscribeVideoStreamInfo method.
type SubscribeCaptureInfoStream: Stream<Item = Result<CaptureInfoResponse, Status>> + Send + Sync + 'static
type SubscribeCaptureInfoStream: Stream<Item = Result<CaptureInfoResponse, Status>> + Send + Sync + 'static
Server streaming response type for the SubscribeCaptureInfo method.
type SubscribeStatusStream: Stream<Item = Result<StatusResponse, Status>> + Send + Sync + 'static
type SubscribeStatusStream: Stream<Item = Result<StatusResponse, Status>> + Send + Sync + 'static
Server streaming response type for the SubscribeStatus method.
type SubscribeCurrentSettingsStream: Stream<Item = Result<CurrentSettingsResponse, Status>> + Send + Sync + 'static
type SubscribeCurrentSettingsStream: Stream<Item = Result<CurrentSettingsResponse, Status>> + Send + Sync + 'static
Server streaming response type for the SubscribeCurrentSettings method.
type SubscribePossibleSettingOptionsStream: Stream<Item = Result<PossibleSettingOptionsResponse, Status>> + Send + Sync + 'static
type SubscribePossibleSettingOptionsStream: Stream<Item = Result<PossibleSettingOptionsResponse, Status>> + Send + Sync + 'static
Server streaming response type for the SubscribePossibleSettingOptions method.
Required methods
fn take_photo<'life0, 'async_trait>(
&'life0 self,
request: Request<TakePhotoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<TakePhotoResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn take_photo<'life0, 'async_trait>(
&'life0 self,
request: Request<TakePhotoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<TakePhotoResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Take one photo.
fn start_photo_interval<'life0, 'async_trait>(
&'life0 self,
request: Request<StartPhotoIntervalRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartPhotoIntervalResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn start_photo_interval<'life0, 'async_trait>(
&'life0 self,
request: Request<StartPhotoIntervalRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartPhotoIntervalResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Start photo timelapse with a given interval.
fn stop_photo_interval<'life0, 'async_trait>(
&'life0 self,
request: Request<StopPhotoIntervalRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopPhotoIntervalResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn stop_photo_interval<'life0, 'async_trait>(
&'life0 self,
request: Request<StopPhotoIntervalRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopPhotoIntervalResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Stop a running photo timelapse.
fn start_video<'life0, 'async_trait>(
&'life0 self,
request: Request<StartVideoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartVideoResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn start_video<'life0, 'async_trait>(
&'life0 self,
request: Request<StartVideoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartVideoResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Start a video recording.
fn stop_video<'life0, 'async_trait>(
&'life0 self,
request: Request<StopVideoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopVideoResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn stop_video<'life0, 'async_trait>(
&'life0 self,
request: Request<StopVideoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopVideoResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Stop a running video recording.
fn start_video_streaming<'life0, 'async_trait>(
&'life0 self,
request: Request<StartVideoStreamingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartVideoStreamingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn start_video_streaming<'life0, 'async_trait>(
&'life0 self,
request: Request<StartVideoStreamingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StartVideoStreamingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Start video streaming.
fn stop_video_streaming<'life0, 'async_trait>(
&'life0 self,
request: Request<StopVideoStreamingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopVideoStreamingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn stop_video_streaming<'life0, 'async_trait>(
&'life0 self,
request: Request<StopVideoStreamingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<StopVideoStreamingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Stop current video streaming.
Set camera mode.
fn subscribe_mode<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeModeRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeModeStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn subscribe_mode<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeModeRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeModeStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Subscribe to camera mode updates.
fn subscribe_information<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeInformationRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeInformationStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn subscribe_information<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeInformationRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeInformationStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Subscribe to camera information updates.
fn subscribe_video_stream_info<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeVideoStreamInfoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeVideoStreamInfoStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn subscribe_video_stream_info<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeVideoStreamInfoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeVideoStreamInfoStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Subscribe to video stream info updates.
fn subscribe_capture_info<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeCaptureInfoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeCaptureInfoStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn subscribe_capture_info<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeCaptureInfoRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeCaptureInfoStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Subscribe to capture info updates.
fn subscribe_status<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeStatusRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeStatusStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn subscribe_status<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeStatusRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeStatusStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Subscribe to camera status updates.
fn subscribe_current_settings<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeCurrentSettingsRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeCurrentSettingsStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn subscribe_current_settings<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribeCurrentSettingsRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribeCurrentSettingsStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Get the list of current camera settings.
fn subscribe_possible_setting_options<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribePossibleSettingOptionsRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribePossibleSettingOptionsStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn subscribe_possible_setting_options<'life0, 'async_trait>(
&'life0 self,
request: Request<SubscribePossibleSettingOptionsRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<Self::SubscribePossibleSettingOptionsStream>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Get the list of settings that can be changed.
fn set_setting<'life0, 'async_trait>(
&'life0 self,
request: Request<SetSettingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<SetSettingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn set_setting<'life0, 'async_trait>(
&'life0 self,
request: Request<SetSettingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<SetSettingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Set a setting to some value.
Only setting_id of setting and option_id of option needs to be set.
fn get_setting<'life0, 'async_trait>(
&'life0 self,
request: Request<GetSettingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<GetSettingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn get_setting<'life0, 'async_trait>(
&'life0 self,
request: Request<GetSettingRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<GetSettingResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Get a setting.
Only setting_id of setting needs to be set.
fn format_storage<'life0, 'async_trait>(
&'life0 self,
request: Request<FormatStorageRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<FormatStorageResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
fn format_storage<'life0, 'async_trait>(
&'life0 self,
request: Request<FormatStorageRequest>
) -> Pin<Box<dyn Future<Output = Result<Response<FormatStorageResponse>, Status>> + Send + 'async_trait>> where
'life0: 'async_trait,
Self: 'async_trait,
Format storage (e.g. SD card) in camera.
This will delete all content of the camera storage!