Trait mav_sdk::grpc::mocap::MocapService[][src]

pub trait MocapService: Send + Sync + 'static {
    fn set_vision_position_estimate<'life0, 'async_trait>(
        &'life0 self,
        request: Request<SetVisionPositionEstimateRequest>
    ) -> Pin<Box<dyn Future<Output = Result<Response<SetVisionPositionEstimateResponse>, Status>> + Send + 'async_trait>>
    where
        'life0: 'async_trait,
        Self: 'async_trait
;
fn set_attitude_position_mocap<'life0, 'async_trait>(
        &'life0 self,
        request: Request<SetAttitudePositionMocapRequest>
    ) -> Pin<Box<dyn Future<Output = Result<Response<SetAttitudePositionMocapResponse>, Status>> + Send + 'async_trait>>
    where
        'life0: 'async_trait,
        Self: 'async_trait
;
fn set_odometry<'life0, 'async_trait>(
        &'life0 self,
        request: Request<SetOdometryRequest>
    ) -> Pin<Box<dyn Future<Output = Result<Response<SetOdometryResponse>, 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 MocapServiceServer.

Required methods

Send Global position/attitude estimate from a vision source.

Send motion capture attitude and position.

Send odometry information with an external interface.

Implementors