CameraServiceClient

Struct CameraServiceClient 

Source
pub struct CameraServiceClient<T> { /* private fields */ }
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§

Source§

impl CameraServiceClient<Channel>

Source

pub async fn connect<D>(dst: D) -> Result<Self, Error>
where D: TryInto<Endpoint>, D::Error: Into<StdError>,

Attempt to create a new client by connecting to a given endpoint.

Source§

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,

Source

pub fn new(inner: T) -> Self

Source

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,

Source

pub fn send_gzip(self) -> Self

Compress requests with gzip.

This requires the server to support it otherwise it might respond with an error.

Source

pub fn accept_gzip(self) -> Self

Enable decompressing responses with gzip.

Source

pub async fn take_photo( &mut self, request: impl IntoRequest<TakePhotoRequest>, ) -> Result<Response<TakePhotoResponse>, Status>

Take one photo.

Source

pub async fn start_photo_interval( &mut self, request: impl IntoRequest<StartPhotoIntervalRequest>, ) -> Result<Response<StartPhotoIntervalResponse>, Status>

Start photo timelapse with a given interval.

Source

pub async fn stop_photo_interval( &mut self, request: impl IntoRequest<StopPhotoIntervalRequest>, ) -> Result<Response<StopPhotoIntervalResponse>, Status>

Stop a running photo timelapse.

Source

pub async fn start_video( &mut self, request: impl IntoRequest<StartVideoRequest>, ) -> Result<Response<StartVideoResponse>, Status>

Start a video recording.

Source

pub async fn stop_video( &mut self, request: impl IntoRequest<StopVideoRequest>, ) -> Result<Response<StopVideoResponse>, Status>

Stop a running video recording.

Source

pub async fn start_video_streaming( &mut self, request: impl IntoRequest<StartVideoStreamingRequest>, ) -> Result<Response<StartVideoStreamingResponse>, Status>

Start video streaming.

Source

pub async fn stop_video_streaming( &mut self, request: impl IntoRequest<StopVideoStreamingRequest>, ) -> Result<Response<StopVideoStreamingResponse>, Status>

Stop current video streaming.

Source

pub async fn set_mode( &mut self, request: impl IntoRequest<SetModeRequest>, ) -> Result<Response<SetModeResponse>, Status>

Set camera mode.

Source

pub async fn subscribe_mode( &mut self, request: impl IntoRequest<SubscribeModeRequest>, ) -> Result<Response<Streaming<ModeResponse>>, Status>

Subscribe to camera mode updates.

Source

pub async fn subscribe_information( &mut self, request: impl IntoRequest<SubscribeInformationRequest>, ) -> Result<Response<Streaming<InformationResponse>>, Status>

Subscribe to camera information updates.

Source

pub async fn subscribe_video_stream_info( &mut self, request: impl IntoRequest<SubscribeVideoStreamInfoRequest>, ) -> Result<Response<Streaming<VideoStreamInfoResponse>>, Status>

Subscribe to video stream info updates.

Source

pub async fn subscribe_capture_info( &mut self, request: impl IntoRequest<SubscribeCaptureInfoRequest>, ) -> Result<Response<Streaming<CaptureInfoResponse>>, Status>

Subscribe to capture info updates.

Source

pub async fn subscribe_status( &mut self, request: impl IntoRequest<SubscribeStatusRequest>, ) -> Result<Response<Streaming<StatusResponse>>, Status>

Subscribe to camera status updates.

Source

pub async fn subscribe_current_settings( &mut self, request: impl IntoRequest<SubscribeCurrentSettingsRequest>, ) -> Result<Response<Streaming<CurrentSettingsResponse>>, Status>

Get the list of current camera settings.

Source

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.

Source

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.

Source

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.

Source

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§

Source§

impl<T: Clone> Clone for CameraServiceClient<T>

Source§

fn clone(&self) -> CameraServiceClient<T>

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl<T: Debug> Debug for CameraServiceClient<T>

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more

Auto Trait Implementations§

§

impl<T> Freeze for CameraServiceClient<T>
where T: Freeze,

§

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§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T> Instrument for T

Source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
Source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T> IntoRequest<T> for T

Source§

fn into_request(self) -> Request<T>

Wrap the input message T in a tonic::Request
Source§

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<V, T> VZip<V> for T
where V: MultiLane<T>,

Source§

fn vzip(self) -> V