Struct mav_sdk::grpc::offboard::offboard_service_client::OffboardServiceClient [−][src]
pub struct OffboardServiceClient<T> { /* fields omitted */ }
Expand description
Control a drone with position, velocity, attitude or motor commands.
The module is called offboard because the commands can be sent from external sources as opposed to onboard control right inside the autopilot “board”.
Client code must specify a setpoint before starting offboard mode. Mavsdk automatically sends setpoints at 20Hz (PX4 Offboard mode requires that setpoints are minimally sent at 2Hz).
Implementations
impl<T> OffboardServiceClient<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> OffboardServiceClient<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
) -> OffboardServiceClient<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 start(
&mut self,
request: impl IntoRequest<StartRequest>
) -> Result<Response<StartResponse>, Status>
pub async fn start(
&mut self,
request: impl IntoRequest<StartRequest>
) -> Result<Response<StartResponse>, Status>
Start offboard control.
pub async fn stop(
&mut self,
request: impl IntoRequest<StopRequest>
) -> Result<Response<StopResponse>, Status>
pub async fn stop(
&mut self,
request: impl IntoRequest<StopRequest>
) -> Result<Response<StopResponse>, Status>
Stop offboard control.
The vehicle will be put into Hold mode: https://docs.px4.io/en/flight_modes/hold.html
pub async fn is_active(
&mut self,
request: impl IntoRequest<IsActiveRequest>
) -> Result<Response<IsActiveResponse>, Status>
pub async fn is_active(
&mut self,
request: impl IntoRequest<IsActiveRequest>
) -> Result<Response<IsActiveResponse>, Status>
Check if offboard control is active.
True means that the vehicle is in offboard mode and we are actively sending setpoints.
pub async fn set_attitude(
&mut self,
request: impl IntoRequest<SetAttitudeRequest>
) -> Result<Response<SetAttitudeResponse>, Status>
pub async fn set_attitude(
&mut self,
request: impl IntoRequest<SetAttitudeRequest>
) -> Result<Response<SetAttitudeResponse>, Status>
Set the attitude in terms of roll, pitch and yaw in degrees with thrust.
pub async fn set_actuator_control(
&mut self,
request: impl IntoRequest<SetActuatorControlRequest>
) -> Result<Response<SetActuatorControlResponse>, Status>
pub async fn set_actuator_control(
&mut self,
request: impl IntoRequest<SetActuatorControlRequest>
) -> Result<Response<SetActuatorControlResponse>, Status>
Set direct actuator control values to groups #0 and #1.
First 8 controls will go to control group 0, the following 8 controls to control group 1 (if actuator_control.num_controls more than 8).
pub async fn set_attitude_rate(
&mut self,
request: impl IntoRequest<SetAttitudeRateRequest>
) -> Result<Response<SetAttitudeRateResponse>, Status>
pub async fn set_attitude_rate(
&mut self,
request: impl IntoRequest<SetAttitudeRateRequest>
) -> Result<Response<SetAttitudeRateResponse>, Status>
Set the attitude rate in terms of pitch, roll and yaw angular rate along with thrust.
pub async fn set_position_ned(
&mut self,
request: impl IntoRequest<SetPositionNedRequest>
) -> Result<Response<SetPositionNedResponse>, Status>
pub async fn set_position_ned(
&mut self,
request: impl IntoRequest<SetPositionNedRequest>
) -> Result<Response<SetPositionNedResponse>, Status>
Set the position in NED coordinates and yaw.
pub async fn set_velocity_body(
&mut self,
request: impl IntoRequest<SetVelocityBodyRequest>
) -> Result<Response<SetVelocityBodyResponse>, Status>
pub async fn set_velocity_body(
&mut self,
request: impl IntoRequest<SetVelocityBodyRequest>
) -> Result<Response<SetVelocityBodyResponse>, Status>
Set the velocity in body coordinates and yaw angular rate. Not available for fixed-wing aircraft.
pub async fn set_velocity_ned(
&mut self,
request: impl IntoRequest<SetVelocityNedRequest>
) -> Result<Response<SetVelocityNedResponse>, Status>
pub async fn set_velocity_ned(
&mut self,
request: impl IntoRequest<SetVelocityNedRequest>
) -> Result<Response<SetVelocityNedResponse>, Status>
Set the velocity in NED coordinates and yaw. Not available for fixed-wing aircraft.
pub async fn set_position_velocity_ned(
&mut self,
request: impl IntoRequest<SetPositionVelocityNedRequest>
) -> Result<Response<SetPositionVelocityNedResponse>, Status>
pub async fn set_position_velocity_ned(
&mut self,
request: impl IntoRequest<SetPositionVelocityNedRequest>
) -> Result<Response<SetPositionVelocityNedResponse>, Status>
Set the position in NED coordinates, with the velocity to be used as feed-forward.
Trait Implementations
Auto Trait Implementations
impl<T> RefUnwindSafe for OffboardServiceClient<T> where
T: RefUnwindSafe,
impl<T> Send for OffboardServiceClient<T> where
T: Send,
impl<T> Sync for OffboardServiceClient<T> where
T: Sync,
impl<T> Unpin for OffboardServiceClient<T> where
T: Unpin,
impl<T> UnwindSafe for OffboardServiceClient<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