Struct mav_sdk::grpc::camera::CameraServiceClient [−][src]
pub struct CameraServiceClient<T> { /* fields omitted */ }
Expand description
Can be used to manage cameras that implement the MAVLink Camera Protocol: https://mavlink.io/en/protocol/camera.html.
Currently only a single camera is supported.
When multiple cameras are supported the plugin will need to be
instantiated separately for every camera and the camera selected using
select_camera
.
Implementations
impl<T> CameraServiceClient<T> where
T: GrpcService<BoxBody>,
T::ResponseBody: Body + Send + Sync + 'static,
T::Error: Into<StdError>,
<T::ResponseBody as Body>::Error: Into<StdError> + Send,
impl<T> CameraServiceClient<T> where
T: GrpcService<BoxBody>,
T::ResponseBody: Body + Send + Sync + 'static,
T::Error: Into<StdError>,
<T::ResponseBody as Body>::Error: Into<StdError> + Send,
pub fn with_interceptor<F>(
inner: T,
interceptor: F
) -> CameraServiceClient<InterceptedService<T, F>> where
F: Interceptor,
T: Service<Request<BoxBody>, Response = Response<<T as GrpcService<BoxBody>>::ResponseBody>>,
<T as Service<Request<BoxBody>>>::Error: Into<StdError> + Send + Sync,
Compress requests with gzip
.
This requires the server to support it otherwise it might respond with an error.
Enable decompressing responses with gzip
.
pub async fn take_photo(
&mut self,
request: impl IntoRequest<TakePhotoRequest>
) -> Result<Response<TakePhotoResponse>, Status>
pub async fn take_photo(
&mut self,
request: impl IntoRequest<TakePhotoRequest>
) -> Result<Response<TakePhotoResponse>, Status>
Take one photo.
pub async fn start_photo_interval(
&mut self,
request: impl IntoRequest<StartPhotoIntervalRequest>
) -> Result<Response<StartPhotoIntervalResponse>, Status>
pub async fn start_photo_interval(
&mut self,
request: impl IntoRequest<StartPhotoIntervalRequest>
) -> Result<Response<StartPhotoIntervalResponse>, Status>
Start photo timelapse with a given interval.
pub async fn stop_photo_interval(
&mut self,
request: impl IntoRequest<StopPhotoIntervalRequest>
) -> Result<Response<StopPhotoIntervalResponse>, Status>
pub async fn stop_photo_interval(
&mut self,
request: impl IntoRequest<StopPhotoIntervalRequest>
) -> Result<Response<StopPhotoIntervalResponse>, Status>
Stop a running photo timelapse.
pub async fn start_video(
&mut self,
request: impl IntoRequest<StartVideoRequest>
) -> Result<Response<StartVideoResponse>, Status>
pub async fn start_video(
&mut self,
request: impl IntoRequest<StartVideoRequest>
) -> Result<Response<StartVideoResponse>, Status>
Start a video recording.
pub async fn stop_video(
&mut self,
request: impl IntoRequest<StopVideoRequest>
) -> Result<Response<StopVideoResponse>, Status>
pub async fn stop_video(
&mut self,
request: impl IntoRequest<StopVideoRequest>
) -> Result<Response<StopVideoResponse>, Status>
Stop a running video recording.
pub async fn start_video_streaming(
&mut self,
request: impl IntoRequest<StartVideoStreamingRequest>
) -> Result<Response<StartVideoStreamingResponse>, Status>
pub async fn start_video_streaming(
&mut self,
request: impl IntoRequest<StartVideoStreamingRequest>
) -> Result<Response<StartVideoStreamingResponse>, Status>
Start video streaming.
pub async fn stop_video_streaming(
&mut self,
request: impl IntoRequest<StopVideoStreamingRequest>
) -> Result<Response<StopVideoStreamingResponse>, Status>
pub async fn stop_video_streaming(
&mut self,
request: impl IntoRequest<StopVideoStreamingRequest>
) -> Result<Response<StopVideoStreamingResponse>, Status>
Stop current video streaming.
pub async fn set_mode(
&mut self,
request: impl IntoRequest<SetModeRequest>
) -> Result<Response<SetModeResponse>, Status>
pub async fn set_mode(
&mut self,
request: impl IntoRequest<SetModeRequest>
) -> Result<Response<SetModeResponse>, Status>
Set camera mode.
pub async fn subscribe_mode(
&mut self,
request: impl IntoRequest<SubscribeModeRequest>
) -> Result<Response<Streaming<ModeResponse>>, Status>
pub async fn subscribe_mode(
&mut self,
request: impl IntoRequest<SubscribeModeRequest>
) -> Result<Response<Streaming<ModeResponse>>, Status>
Subscribe to camera mode updates.
pub async fn subscribe_information(
&mut self,
request: impl IntoRequest<SubscribeInformationRequest>
) -> Result<Response<Streaming<InformationResponse>>, Status>
pub async fn subscribe_information(
&mut self,
request: impl IntoRequest<SubscribeInformationRequest>
) -> Result<Response<Streaming<InformationResponse>>, Status>
Subscribe to camera information updates.
pub async fn subscribe_video_stream_info(
&mut self,
request: impl IntoRequest<SubscribeVideoStreamInfoRequest>
) -> Result<Response<Streaming<VideoStreamInfoResponse>>, Status>
pub async fn subscribe_video_stream_info(
&mut self,
request: impl IntoRequest<SubscribeVideoStreamInfoRequest>
) -> Result<Response<Streaming<VideoStreamInfoResponse>>, Status>
Subscribe to video stream info updates.
pub async fn subscribe_capture_info(
&mut self,
request: impl IntoRequest<SubscribeCaptureInfoRequest>
) -> Result<Response<Streaming<CaptureInfoResponse>>, Status>
pub async fn subscribe_capture_info(
&mut self,
request: impl IntoRequest<SubscribeCaptureInfoRequest>
) -> Result<Response<Streaming<CaptureInfoResponse>>, Status>
Subscribe to capture info updates.
pub async fn subscribe_status(
&mut self,
request: impl IntoRequest<SubscribeStatusRequest>
) -> Result<Response<Streaming<StatusResponse>>, Status>
pub async fn subscribe_status(
&mut self,
request: impl IntoRequest<SubscribeStatusRequest>
) -> Result<Response<Streaming<StatusResponse>>, Status>
Subscribe to camera status updates.
pub async fn subscribe_current_settings(
&mut self,
request: impl IntoRequest<SubscribeCurrentSettingsRequest>
) -> Result<Response<Streaming<CurrentSettingsResponse>>, Status>
pub async fn subscribe_current_settings(
&mut self,
request: impl IntoRequest<SubscribeCurrentSettingsRequest>
) -> Result<Response<Streaming<CurrentSettingsResponse>>, Status>
Get the list of current camera settings.
pub async fn subscribe_possible_setting_options(
&mut self,
request: impl IntoRequest<SubscribePossibleSettingOptionsRequest>
) -> Result<Response<Streaming<PossibleSettingOptionsResponse>>, Status>
pub async fn subscribe_possible_setting_options(
&mut self,
request: impl IntoRequest<SubscribePossibleSettingOptionsRequest>
) -> Result<Response<Streaming<PossibleSettingOptionsResponse>>, Status>
Get the list of settings that can be changed.
pub async fn set_setting(
&mut self,
request: impl IntoRequest<SetSettingRequest>
) -> Result<Response<SetSettingResponse>, Status>
pub async fn set_setting(
&mut self,
request: impl IntoRequest<SetSettingRequest>
) -> Result<Response<SetSettingResponse>, Status>
Set a setting to some value.
Only setting_id of setting and option_id of option needs to be set.
pub async fn get_setting(
&mut self,
request: impl IntoRequest<GetSettingRequest>
) -> Result<Response<GetSettingResponse>, Status>
pub async fn get_setting(
&mut self,
request: impl IntoRequest<GetSettingRequest>
) -> Result<Response<GetSettingResponse>, Status>
Get a setting.
Only setting_id of setting needs to be set.
pub async fn format_storage(
&mut self,
request: impl IntoRequest<FormatStorageRequest>
) -> Result<Response<FormatStorageResponse>, Status>
pub async fn format_storage(
&mut self,
request: impl IntoRequest<FormatStorageRequest>
) -> Result<Response<FormatStorageResponse>, Status>
Format storage (e.g. SD card) in camera.
This will delete all content of the camera storage!
Trait Implementations
Auto Trait Implementations
impl<T> RefUnwindSafe for CameraServiceClient<T> where
T: RefUnwindSafe,
impl<T> Send for CameraServiceClient<T> where
T: Send,
impl<T> Sync for CameraServiceClient<T> where
T: Sync,
impl<T> Unpin for CameraServiceClient<T> where
T: Unpin,
impl<T> UnwindSafe for CameraServiceClient<T> where
T: UnwindSafe,
Blanket Implementations
Mutably borrows from an owned value. Read more
Instruments this type with the provided Span
, returning an
Instrumented
wrapper. Read more
Wrap the input message T
in a tonic::Request