1#[derive(Clone, PartialEq, ::prost::Message)]
2pub struct ArmRequest {}
3#[derive(Clone, PartialEq, ::prost::Message)]
4pub struct ArmResponse {
5 #[prost(message, optional, tag = "1")]
6 pub action_result: ::core::option::Option<ActionResult>,
7}
8#[derive(Clone, PartialEq, ::prost::Message)]
9pub struct DisarmRequest {}
10#[derive(Clone, PartialEq, ::prost::Message)]
11pub struct DisarmResponse {
12 #[prost(message, optional, tag = "1")]
13 pub action_result: ::core::option::Option<ActionResult>,
14}
15#[derive(Clone, PartialEq, ::prost::Message)]
16pub struct TakeoffRequest {}
17#[derive(Clone, PartialEq, ::prost::Message)]
18pub struct TakeoffResponse {
19 #[prost(message, optional, tag = "1")]
20 pub action_result: ::core::option::Option<ActionResult>,
21}
22#[derive(Clone, PartialEq, ::prost::Message)]
23pub struct LandRequest {}
24#[derive(Clone, PartialEq, ::prost::Message)]
25pub struct LandResponse {
26 #[prost(message, optional, tag = "1")]
27 pub action_result: ::core::option::Option<ActionResult>,
28}
29#[derive(Clone, PartialEq, ::prost::Message)]
30pub struct RebootRequest {}
31#[derive(Clone, PartialEq, ::prost::Message)]
32pub struct RebootResponse {
33 #[prost(message, optional, tag = "1")]
34 pub action_result: ::core::option::Option<ActionResult>,
35}
36#[derive(Clone, PartialEq, ::prost::Message)]
37pub struct ShutdownRequest {}
38#[derive(Clone, PartialEq, ::prost::Message)]
39pub struct ShutdownResponse {
40 #[prost(message, optional, tag = "1")]
41 pub action_result: ::core::option::Option<ActionResult>,
42}
43#[derive(Clone, PartialEq, ::prost::Message)]
44pub struct TerminateRequest {}
45#[derive(Clone, PartialEq, ::prost::Message)]
46pub struct TerminateResponse {
47 #[prost(message, optional, tag = "1")]
48 pub action_result: ::core::option::Option<ActionResult>,
49}
50#[derive(Clone, PartialEq, ::prost::Message)]
51pub struct KillRequest {}
52#[derive(Clone, PartialEq, ::prost::Message)]
53pub struct KillResponse {
54 #[prost(message, optional, tag = "1")]
55 pub action_result: ::core::option::Option<ActionResult>,
56}
57#[derive(Clone, PartialEq, ::prost::Message)]
58pub struct ReturnToLaunchRequest {}
59#[derive(Clone, PartialEq, ::prost::Message)]
60pub struct ReturnToLaunchResponse {
61 #[prost(message, optional, tag = "1")]
62 pub action_result: ::core::option::Option<ActionResult>,
63}
64#[derive(Clone, PartialEq, ::prost::Message)]
65pub struct GotoLocationRequest {
66 #[prost(double, tag = "1")]
68 pub latitude_deg: f64,
69 #[prost(double, tag = "2")]
71 pub longitude_deg: f64,
72 #[prost(float, tag = "3")]
74 pub absolute_altitude_m: f32,
75 #[prost(float, tag = "4")]
77 pub yaw_deg: f32,
78}
79#[derive(Clone, PartialEq, ::prost::Message)]
80pub struct GotoLocationResponse {
81 #[prost(message, optional, tag = "1")]
82 pub action_result: ::core::option::Option<ActionResult>,
83}
84#[derive(Clone, PartialEq, ::prost::Message)]
85pub struct TransitionToFixedwingRequest {}
86#[derive(Clone, PartialEq, ::prost::Message)]
87pub struct TransitionToFixedwingResponse {
88 #[prost(message, optional, tag = "1")]
89 pub action_result: ::core::option::Option<ActionResult>,
90}
91#[derive(Clone, PartialEq, ::prost::Message)]
92pub struct TransitionToMulticopterRequest {}
93#[derive(Clone, PartialEq, ::prost::Message)]
94pub struct TransitionToMulticopterResponse {
95 #[prost(message, optional, tag = "1")]
96 pub action_result: ::core::option::Option<ActionResult>,
97}
98#[derive(Clone, PartialEq, ::prost::Message)]
99pub struct GetTakeoffAltitudeRequest {}
100#[derive(Clone, PartialEq, ::prost::Message)]
101pub struct GetTakeoffAltitudeResponse {
102 #[prost(message, optional, tag = "1")]
103 pub action_result: ::core::option::Option<ActionResult>,
104 #[prost(float, tag = "2")]
106 pub altitude: f32,
107}
108#[derive(Clone, PartialEq, ::prost::Message)]
109pub struct SetTakeoffAltitudeRequest {
110 #[prost(float, tag = "1")]
112 pub altitude: f32,
113}
114#[derive(Clone, PartialEq, ::prost::Message)]
115pub struct SetTakeoffAltitudeResponse {
116 #[prost(message, optional, tag = "1")]
117 pub action_result: ::core::option::Option<ActionResult>,
118}
119#[derive(Clone, PartialEq, ::prost::Message)]
120pub struct GetMaximumSpeedRequest {}
121#[derive(Clone, PartialEq, ::prost::Message)]
122pub struct GetMaximumSpeedResponse {
123 #[prost(message, optional, tag = "1")]
124 pub action_result: ::core::option::Option<ActionResult>,
125 #[prost(float, tag = "2")]
127 pub speed: f32,
128}
129#[derive(Clone, PartialEq, ::prost::Message)]
130pub struct SetMaximumSpeedRequest {
131 #[prost(float, tag = "1")]
133 pub speed: f32,
134}
135#[derive(Clone, PartialEq, ::prost::Message)]
136pub struct SetMaximumSpeedResponse {
137 #[prost(message, optional, tag = "1")]
138 pub action_result: ::core::option::Option<ActionResult>,
139}
140#[derive(Clone, PartialEq, ::prost::Message)]
141pub struct GetReturnToLaunchAltitudeRequest {}
142#[derive(Clone, PartialEq, ::prost::Message)]
143pub struct GetReturnToLaunchAltitudeResponse {
144 #[prost(message, optional, tag = "1")]
145 pub action_result: ::core::option::Option<ActionResult>,
146 #[prost(float, tag = "2")]
148 pub relative_altitude_m: f32,
149}
150#[derive(Clone, PartialEq, ::prost::Message)]
151pub struct SetReturnToLaunchAltitudeRequest {
152 #[prost(float, tag = "1")]
154 pub relative_altitude_m: f32,
155}
156#[derive(Clone, PartialEq, ::prost::Message)]
157pub struct SetReturnToLaunchAltitudeResponse {
158 #[prost(message, optional, tag = "1")]
159 pub action_result: ::core::option::Option<ActionResult>,
160}
161#[derive(Clone, PartialEq, ::prost::Message)]
163pub struct ActionResult {
164 #[prost(enumeration = "action_result::Result", tag = "1")]
166 pub result: i32,
167 #[prost(string, tag = "2")]
169 pub result_str: ::prost::alloc::string::String,
170}
171pub mod action_result {
173 #[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
175 #[repr(i32)]
176 pub enum Result {
177 Unknown = 0,
179 Success = 1,
181 NoSystem = 2,
183 ConnectionError = 3,
185 Busy = 4,
187 CommandDenied = 5,
189 CommandDeniedLandedStateUnknown = 6,
191 CommandDeniedNotLanded = 7,
193 Timeout = 8,
195 VtolTransitionSupportUnknown = 9,
197 NoVtolTransitionSupport = 10,
199 ParameterError = 11,
201 }
202}
203#[doc = r" Generated client implementations."]
204pub mod action_service_client {
205 #![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
206 use tonic::codegen::*;
207 #[doc = " Enable simple actions such as arming, taking off, and landing."]
208 #[derive(Debug, Clone)]
209 pub struct ActionServiceClient<T> {
210 inner: tonic::client::Grpc<T>,
211 }
212 impl ActionServiceClient<tonic::transport::Channel> {
213 #[doc = r" Attempt to create a new client by connecting to a given endpoint."]
214 pub async fn connect<D>(dst: D) -> Result<Self, tonic::transport::Error>
215 where
216 D: std::convert::TryInto<tonic::transport::Endpoint>,
217 D::Error: Into<StdError>,
218 {
219 let conn = tonic::transport::Endpoint::new(dst)?.connect().await?;
220 Ok(Self::new(conn))
221 }
222 }
223 impl<T> ActionServiceClient<T>
224 where
225 T: tonic::client::GrpcService<tonic::body::BoxBody>,
226 T::ResponseBody: Body + Send + Sync + 'static,
227 T::Error: Into<StdError>,
228 <T::ResponseBody as Body>::Error: Into<StdError> + Send,
229 {
230 pub fn new(inner: T) -> Self {
231 let inner = tonic::client::Grpc::new(inner);
232 Self { inner }
233 }
234 pub fn with_interceptor<F>(
235 inner: T,
236 interceptor: F,
237 ) -> ActionServiceClient<InterceptedService<T, F>>
238 where
239 F: tonic::service::Interceptor,
240 T: tonic::codegen::Service<
241 http::Request<tonic::body::BoxBody>,
242 Response = http::Response<
243 <T as tonic::client::GrpcService<tonic::body::BoxBody>>::ResponseBody,
244 >,
245 >,
246 <T as tonic::codegen::Service<http::Request<tonic::body::BoxBody>>>::Error:
247 Into<StdError> + Send + Sync,
248 {
249 ActionServiceClient::new(InterceptedService::new(inner, interceptor))
250 }
251 #[doc = r" Compress requests with `gzip`."]
252 #[doc = r""]
253 #[doc = r" This requires the server to support it otherwise it might respond with an"]
254 #[doc = r" error."]
255 pub fn send_gzip(mut self) -> Self {
256 self.inner = self.inner.send_gzip();
257 self
258 }
259 #[doc = r" Enable decompressing responses with `gzip`."]
260 pub fn accept_gzip(mut self) -> Self {
261 self.inner = self.inner.accept_gzip();
262 self
263 }
264 #[doc = ""]
265 #[doc = " Send command to arm the drone."]
266 #[doc = ""]
267 #[doc = " Arming a drone normally causes motors to spin at idle."]
268 #[doc = " Before arming take all safety precautions and stand clear of the drone!"]
269 pub async fn arm(
270 &mut self,
271 request: impl tonic::IntoRequest<super::ArmRequest>,
272 ) -> Result<tonic::Response<super::ArmResponse>, tonic::Status> {
273 self.inner.ready().await.map_err(|e| {
274 tonic::Status::new(
275 tonic::Code::Unknown,
276 format!("Service was not ready: {}", e.into()),
277 )
278 })?;
279 let codec = tonic::codec::ProstCodec::default();
280 let path = http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Arm");
281 self.inner.unary(request.into_request(), path, codec).await
282 }
283 #[doc = ""]
284 #[doc = " Send command to disarm the drone."]
285 #[doc = ""]
286 #[doc = " This will disarm a drone that considers itself landed. If flying, the drone should"]
287 #[doc = " reject the disarm command. Disarming means that all motors will stop."]
288 pub async fn disarm(
289 &mut self,
290 request: impl tonic::IntoRequest<super::DisarmRequest>,
291 ) -> Result<tonic::Response<super::DisarmResponse>, tonic::Status> {
292 self.inner.ready().await.map_err(|e| {
293 tonic::Status::new(
294 tonic::Code::Unknown,
295 format!("Service was not ready: {}", e.into()),
296 )
297 })?;
298 let codec = tonic::codec::ProstCodec::default();
299 let path =
300 http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Disarm");
301 self.inner.unary(request.into_request(), path, codec).await
302 }
303 #[doc = ""]
304 #[doc = " Send command to take off and hover."]
305 #[doc = ""]
306 #[doc = " This switches the drone into position control mode and commands"]
307 #[doc = " it to take off and hover at the takeoff altitude."]
308 #[doc = ""]
309 #[doc = " Note that the vehicle must be armed before it can take off."]
310 pub async fn takeoff(
311 &mut self,
312 request: impl tonic::IntoRequest<super::TakeoffRequest>,
313 ) -> Result<tonic::Response<super::TakeoffResponse>, tonic::Status> {
314 self.inner.ready().await.map_err(|e| {
315 tonic::Status::new(
316 tonic::Code::Unknown,
317 format!("Service was not ready: {}", e.into()),
318 )
319 })?;
320 let codec = tonic::codec::ProstCodec::default();
321 let path =
322 http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Takeoff");
323 self.inner.unary(request.into_request(), path, codec).await
324 }
325 #[doc = ""]
326 #[doc = " Send command to land at the current position."]
327 #[doc = ""]
328 #[doc = " This switches the drone to 'Land' flight mode."]
329 pub async fn land(
330 &mut self,
331 request: impl tonic::IntoRequest<super::LandRequest>,
332 ) -> Result<tonic::Response<super::LandResponse>, tonic::Status> {
333 self.inner.ready().await.map_err(|e| {
334 tonic::Status::new(
335 tonic::Code::Unknown,
336 format!("Service was not ready: {}", e.into()),
337 )
338 })?;
339 let codec = tonic::codec::ProstCodec::default();
340 let path =
341 http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Land");
342 self.inner.unary(request.into_request(), path, codec).await
343 }
344 #[doc = ""]
345 #[doc = " Send command to reboot the drone components."]
346 #[doc = ""]
347 #[doc = " This will reboot the autopilot, companion computer, camera and gimbal."]
348 pub async fn reboot(
349 &mut self,
350 request: impl tonic::IntoRequest<super::RebootRequest>,
351 ) -> Result<tonic::Response<super::RebootResponse>, tonic::Status> {
352 self.inner.ready().await.map_err(|e| {
353 tonic::Status::new(
354 tonic::Code::Unknown,
355 format!("Service was not ready: {}", e.into()),
356 )
357 })?;
358 let codec = tonic::codec::ProstCodec::default();
359 let path =
360 http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Reboot");
361 self.inner.unary(request.into_request(), path, codec).await
362 }
363 #[doc = ""]
364 #[doc = " Send command to shut down the drone components."]
365 #[doc = ""]
366 #[doc = " This will shut down the autopilot, onboard computer, camera and gimbal."]
367 #[doc = " This command should only be used when the autopilot is disarmed and autopilots commonly"]
368 #[doc = " reject it if they are not already ready to shut down."]
369 pub async fn shutdown(
370 &mut self,
371 request: impl tonic::IntoRequest<super::ShutdownRequest>,
372 ) -> Result<tonic::Response<super::ShutdownResponse>, tonic::Status> {
373 self.inner.ready().await.map_err(|e| {
374 tonic::Status::new(
375 tonic::Code::Unknown,
376 format!("Service was not ready: {}", e.into()),
377 )
378 })?;
379 let codec = tonic::codec::ProstCodec::default();
380 let path =
381 http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Shutdown");
382 self.inner.unary(request.into_request(), path, codec).await
383 }
384 #[doc = ""]
385 #[doc = " Send command to terminate the drone."]
386 #[doc = ""]
387 #[doc = " This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute)."]
388 pub async fn terminate(
389 &mut self,
390 request: impl tonic::IntoRequest<super::TerminateRequest>,
391 ) -> Result<tonic::Response<super::TerminateResponse>, tonic::Status> {
392 self.inner.ready().await.map_err(|e| {
393 tonic::Status::new(
394 tonic::Code::Unknown,
395 format!("Service was not ready: {}", e.into()),
396 )
397 })?;
398 let codec = tonic::codec::ProstCodec::default();
399 let path =
400 http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Terminate");
401 self.inner.unary(request.into_request(), path, codec).await
402 }
403 #[doc = ""]
404 #[doc = " Send command to kill the drone."]
405 #[doc = ""]
406 #[doc = " This will disarm a drone irrespective of whether it is landed or flying."]
407 #[doc = " Note that the drone will fall out of the sky if this command is used while flying."]
408 pub async fn kill(
409 &mut self,
410 request: impl tonic::IntoRequest<super::KillRequest>,
411 ) -> Result<tonic::Response<super::KillResponse>, tonic::Status> {
412 self.inner.ready().await.map_err(|e| {
413 tonic::Status::new(
414 tonic::Code::Unknown,
415 format!("Service was not ready: {}", e.into()),
416 )
417 })?;
418 let codec = tonic::codec::ProstCodec::default();
419 let path =
420 http::uri::PathAndQuery::from_static("/mavsdk.rpc.action.ActionService/Kill");
421 self.inner.unary(request.into_request(), path, codec).await
422 }
423 #[doc = ""]
424 #[doc = " Send command to return to the launch (takeoff) position and land."]
425 #[doc = ""]
426 #[doc = " This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.html) which"]
427 #[doc = " generally means it will rise up to a certain altitude to clear any obstacles before heading"]
428 #[doc = " back to the launch (takeoff) position and land there."]
429 pub async fn return_to_launch(
430 &mut self,
431 request: impl tonic::IntoRequest<super::ReturnToLaunchRequest>,
432 ) -> Result<tonic::Response<super::ReturnToLaunchResponse>, tonic::Status> {
433 self.inner.ready().await.map_err(|e| {
434 tonic::Status::new(
435 tonic::Code::Unknown,
436 format!("Service was not ready: {}", e.into()),
437 )
438 })?;
439 let codec = tonic::codec::ProstCodec::default();
440 let path = http::uri::PathAndQuery::from_static(
441 "/mavsdk.rpc.action.ActionService/ReturnToLaunch",
442 );
443 self.inner.unary(request.into_request(), path, codec).await
444 }
445 #[doc = ""]
446 #[doc = " Send command to move the vehicle to a specific global position."]
447 #[doc = ""]
448 #[doc = " The latitude and longitude are given in degrees (WGS84 frame) and the altitude"]
449 #[doc = " in meters AMSL (above mean sea level)."]
450 #[doc = ""]
451 #[doc = " The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise)."]
452 pub async fn goto_location(
453 &mut self,
454 request: impl tonic::IntoRequest<super::GotoLocationRequest>,
455 ) -> Result<tonic::Response<super::GotoLocationResponse>, tonic::Status> {
456 self.inner.ready().await.map_err(|e| {
457 tonic::Status::new(
458 tonic::Code::Unknown,
459 format!("Service was not ready: {}", e.into()),
460 )
461 })?;
462 let codec = tonic::codec::ProstCodec::default();
463 let path = http::uri::PathAndQuery::from_static(
464 "/mavsdk.rpc.action.ActionService/GotoLocation",
465 );
466 self.inner.unary(request.into_request(), path, codec).await
467 }
468 #[doc = ""]
469 #[doc = " Send command to transition the drone to fixedwing."]
470 #[doc = ""]
471 #[doc = " The associated action will only be executed for VTOL vehicles (on other vehicle types the"]
472 #[doc = " command will fail). The command will succeed if called when the vehicle"]
473 #[doc = " is already in fixedwing mode."]
474 pub async fn transition_to_fixedwing(
475 &mut self,
476 request: impl tonic::IntoRequest<super::TransitionToFixedwingRequest>,
477 ) -> Result<tonic::Response<super::TransitionToFixedwingResponse>, tonic::Status> {
478 self.inner.ready().await.map_err(|e| {
479 tonic::Status::new(
480 tonic::Code::Unknown,
481 format!("Service was not ready: {}", e.into()),
482 )
483 })?;
484 let codec = tonic::codec::ProstCodec::default();
485 let path = http::uri::PathAndQuery::from_static(
486 "/mavsdk.rpc.action.ActionService/TransitionToFixedwing",
487 );
488 self.inner.unary(request.into_request(), path, codec).await
489 }
490 #[doc = ""]
491 #[doc = " Send command to transition the drone to multicopter."]
492 #[doc = ""]
493 #[doc = " The associated action will only be executed for VTOL vehicles (on other vehicle types the"]
494 #[doc = " command will fail). The command will succeed if called when the vehicle"]
495 #[doc = " is already in multicopter mode."]
496 pub async fn transition_to_multicopter(
497 &mut self,
498 request: impl tonic::IntoRequest<super::TransitionToMulticopterRequest>,
499 ) -> Result<tonic::Response<super::TransitionToMulticopterResponse>, tonic::Status>
500 {
501 self.inner.ready().await.map_err(|e| {
502 tonic::Status::new(
503 tonic::Code::Unknown,
504 format!("Service was not ready: {}", e.into()),
505 )
506 })?;
507 let codec = tonic::codec::ProstCodec::default();
508 let path = http::uri::PathAndQuery::from_static(
509 "/mavsdk.rpc.action.ActionService/TransitionToMulticopter",
510 );
511 self.inner.unary(request.into_request(), path, codec).await
512 }
513 #[doc = ""]
514 #[doc = " Get the takeoff altitude (in meters above ground)."]
515 pub async fn get_takeoff_altitude(
516 &mut self,
517 request: impl tonic::IntoRequest<super::GetTakeoffAltitudeRequest>,
518 ) -> Result<tonic::Response<super::GetTakeoffAltitudeResponse>, tonic::Status> {
519 self.inner.ready().await.map_err(|e| {
520 tonic::Status::new(
521 tonic::Code::Unknown,
522 format!("Service was not ready: {}", e.into()),
523 )
524 })?;
525 let codec = tonic::codec::ProstCodec::default();
526 let path = http::uri::PathAndQuery::from_static(
527 "/mavsdk.rpc.action.ActionService/GetTakeoffAltitude",
528 );
529 self.inner.unary(request.into_request(), path, codec).await
530 }
531 #[doc = ""]
532 #[doc = " Set takeoff altitude (in meters above ground)."]
533 pub async fn set_takeoff_altitude(
534 &mut self,
535 request: impl tonic::IntoRequest<super::SetTakeoffAltitudeRequest>,
536 ) -> Result<tonic::Response<super::SetTakeoffAltitudeResponse>, tonic::Status> {
537 self.inner.ready().await.map_err(|e| {
538 tonic::Status::new(
539 tonic::Code::Unknown,
540 format!("Service was not ready: {}", e.into()),
541 )
542 })?;
543 let codec = tonic::codec::ProstCodec::default();
544 let path = http::uri::PathAndQuery::from_static(
545 "/mavsdk.rpc.action.ActionService/SetTakeoffAltitude",
546 );
547 self.inner.unary(request.into_request(), path, codec).await
548 }
549 #[doc = ""]
550 #[doc = " Get the vehicle maximum speed (in metres/second)."]
551 pub async fn get_maximum_speed(
552 &mut self,
553 request: impl tonic::IntoRequest<super::GetMaximumSpeedRequest>,
554 ) -> Result<tonic::Response<super::GetMaximumSpeedResponse>, tonic::Status> {
555 self.inner.ready().await.map_err(|e| {
556 tonic::Status::new(
557 tonic::Code::Unknown,
558 format!("Service was not ready: {}", e.into()),
559 )
560 })?;
561 let codec = tonic::codec::ProstCodec::default();
562 let path = http::uri::PathAndQuery::from_static(
563 "/mavsdk.rpc.action.ActionService/GetMaximumSpeed",
564 );
565 self.inner.unary(request.into_request(), path, codec).await
566 }
567 #[doc = ""]
568 #[doc = " Set vehicle maximum speed (in metres/second)."]
569 pub async fn set_maximum_speed(
570 &mut self,
571 request: impl tonic::IntoRequest<super::SetMaximumSpeedRequest>,
572 ) -> Result<tonic::Response<super::SetMaximumSpeedResponse>, tonic::Status> {
573 self.inner.ready().await.map_err(|e| {
574 tonic::Status::new(
575 tonic::Code::Unknown,
576 format!("Service was not ready: {}", e.into()),
577 )
578 })?;
579 let codec = tonic::codec::ProstCodec::default();
580 let path = http::uri::PathAndQuery::from_static(
581 "/mavsdk.rpc.action.ActionService/SetMaximumSpeed",
582 );
583 self.inner.unary(request.into_request(), path, codec).await
584 }
585 #[doc = ""]
586 #[doc = " Get the return to launch minimum return altitude (in meters)."]
587 pub async fn get_return_to_launch_altitude(
588 &mut self,
589 request: impl tonic::IntoRequest<super::GetReturnToLaunchAltitudeRequest>,
590 ) -> Result<tonic::Response<super::GetReturnToLaunchAltitudeResponse>, tonic::Status>
591 {
592 self.inner.ready().await.map_err(|e| {
593 tonic::Status::new(
594 tonic::Code::Unknown,
595 format!("Service was not ready: {}", e.into()),
596 )
597 })?;
598 let codec = tonic::codec::ProstCodec::default();
599 let path = http::uri::PathAndQuery::from_static(
600 "/mavsdk.rpc.action.ActionService/GetReturnToLaunchAltitude",
601 );
602 self.inner.unary(request.into_request(), path, codec).await
603 }
604 #[doc = ""]
605 #[doc = " Set the return to launch minimum return altitude (in meters)."]
606 pub async fn set_return_to_launch_altitude(
607 &mut self,
608 request: impl tonic::IntoRequest<super::SetReturnToLaunchAltitudeRequest>,
609 ) -> Result<tonic::Response<super::SetReturnToLaunchAltitudeResponse>, tonic::Status>
610 {
611 self.inner.ready().await.map_err(|e| {
612 tonic::Status::new(
613 tonic::Code::Unknown,
614 format!("Service was not ready: {}", e.into()),
615 )
616 })?;
617 let codec = tonic::codec::ProstCodec::default();
618 let path = http::uri::PathAndQuery::from_static(
619 "/mavsdk.rpc.action.ActionService/SetReturnToLaunchAltitude",
620 );
621 self.inner.unary(request.into_request(), path, codec).await
622 }
623 }
624}
625#[doc = r" Generated server implementations."]
626pub mod action_service_server {
627 #![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
628 use tonic::codegen::*;
629 #[doc = "Generated trait containing gRPC methods that should be implemented for use with ActionServiceServer."]
630 #[async_trait]
631 pub trait ActionService: Send + Sync + 'static {
632 #[doc = ""]
633 #[doc = " Send command to arm the drone."]
634 #[doc = ""]
635 #[doc = " Arming a drone normally causes motors to spin at idle."]
636 #[doc = " Before arming take all safety precautions and stand clear of the drone!"]
637 async fn arm(
638 &self,
639 request: tonic::Request<super::ArmRequest>,
640 ) -> Result<tonic::Response<super::ArmResponse>, tonic::Status>;
641 #[doc = ""]
642 #[doc = " Send command to disarm the drone."]
643 #[doc = ""]
644 #[doc = " This will disarm a drone that considers itself landed. If flying, the drone should"]
645 #[doc = " reject the disarm command. Disarming means that all motors will stop."]
646 async fn disarm(
647 &self,
648 request: tonic::Request<super::DisarmRequest>,
649 ) -> Result<tonic::Response<super::DisarmResponse>, tonic::Status>;
650 #[doc = ""]
651 #[doc = " Send command to take off and hover."]
652 #[doc = ""]
653 #[doc = " This switches the drone into position control mode and commands"]
654 #[doc = " it to take off and hover at the takeoff altitude."]
655 #[doc = ""]
656 #[doc = " Note that the vehicle must be armed before it can take off."]
657 async fn takeoff(
658 &self,
659 request: tonic::Request<super::TakeoffRequest>,
660 ) -> Result<tonic::Response<super::TakeoffResponse>, tonic::Status>;
661 #[doc = ""]
662 #[doc = " Send command to land at the current position."]
663 #[doc = ""]
664 #[doc = " This switches the drone to 'Land' flight mode."]
665 async fn land(
666 &self,
667 request: tonic::Request<super::LandRequest>,
668 ) -> Result<tonic::Response<super::LandResponse>, tonic::Status>;
669 #[doc = ""]
670 #[doc = " Send command to reboot the drone components."]
671 #[doc = ""]
672 #[doc = " This will reboot the autopilot, companion computer, camera and gimbal."]
673 async fn reboot(
674 &self,
675 request: tonic::Request<super::RebootRequest>,
676 ) -> Result<tonic::Response<super::RebootResponse>, tonic::Status>;
677 #[doc = ""]
678 #[doc = " Send command to shut down the drone components."]
679 #[doc = ""]
680 #[doc = " This will shut down the autopilot, onboard computer, camera and gimbal."]
681 #[doc = " This command should only be used when the autopilot is disarmed and autopilots commonly"]
682 #[doc = " reject it if they are not already ready to shut down."]
683 async fn shutdown(
684 &self,
685 request: tonic::Request<super::ShutdownRequest>,
686 ) -> Result<tonic::Response<super::ShutdownResponse>, tonic::Status>;
687 #[doc = ""]
688 #[doc = " Send command to terminate the drone."]
689 #[doc = ""]
690 #[doc = " This will run the terminate routine as configured on the drone (e.g. disarm and open the parachute)."]
691 async fn terminate(
692 &self,
693 request: tonic::Request<super::TerminateRequest>,
694 ) -> Result<tonic::Response<super::TerminateResponse>, tonic::Status>;
695 #[doc = ""]
696 #[doc = " Send command to kill the drone."]
697 #[doc = ""]
698 #[doc = " This will disarm a drone irrespective of whether it is landed or flying."]
699 #[doc = " Note that the drone will fall out of the sky if this command is used while flying."]
700 async fn kill(
701 &self,
702 request: tonic::Request<super::KillRequest>,
703 ) -> Result<tonic::Response<super::KillResponse>, tonic::Status>;
704 #[doc = ""]
705 #[doc = " Send command to return to the launch (takeoff) position and land."]
706 #[doc = ""]
707 #[doc = " This switches the drone into [Return mode](https://docs.px4.io/master/en/flight_modes/return.html) which"]
708 #[doc = " generally means it will rise up to a certain altitude to clear any obstacles before heading"]
709 #[doc = " back to the launch (takeoff) position and land there."]
710 async fn return_to_launch(
711 &self,
712 request: tonic::Request<super::ReturnToLaunchRequest>,
713 ) -> Result<tonic::Response<super::ReturnToLaunchResponse>, tonic::Status>;
714 #[doc = ""]
715 #[doc = " Send command to move the vehicle to a specific global position."]
716 #[doc = ""]
717 #[doc = " The latitude and longitude are given in degrees (WGS84 frame) and the altitude"]
718 #[doc = " in meters AMSL (above mean sea level)."]
719 #[doc = ""]
720 #[doc = " The yaw angle is in degrees (frame is NED, 0 is North, positive is clockwise)."]
721 async fn goto_location(
722 &self,
723 request: tonic::Request<super::GotoLocationRequest>,
724 ) -> Result<tonic::Response<super::GotoLocationResponse>, tonic::Status>;
725 #[doc = ""]
726 #[doc = " Send command to transition the drone to fixedwing."]
727 #[doc = ""]
728 #[doc = " The associated action will only be executed for VTOL vehicles (on other vehicle types the"]
729 #[doc = " command will fail). The command will succeed if called when the vehicle"]
730 #[doc = " is already in fixedwing mode."]
731 async fn transition_to_fixedwing(
732 &self,
733 request: tonic::Request<super::TransitionToFixedwingRequest>,
734 ) -> Result<tonic::Response<super::TransitionToFixedwingResponse>, tonic::Status>;
735 #[doc = ""]
736 #[doc = " Send command to transition the drone to multicopter."]
737 #[doc = ""]
738 #[doc = " The associated action will only be executed for VTOL vehicles (on other vehicle types the"]
739 #[doc = " command will fail). The command will succeed if called when the vehicle"]
740 #[doc = " is already in multicopter mode."]
741 async fn transition_to_multicopter(
742 &self,
743 request: tonic::Request<super::TransitionToMulticopterRequest>,
744 ) -> Result<tonic::Response<super::TransitionToMulticopterResponse>, tonic::Status>;
745 #[doc = ""]
746 #[doc = " Get the takeoff altitude (in meters above ground)."]
747 async fn get_takeoff_altitude(
748 &self,
749 request: tonic::Request<super::GetTakeoffAltitudeRequest>,
750 ) -> Result<tonic::Response<super::GetTakeoffAltitudeResponse>, tonic::Status>;
751 #[doc = ""]
752 #[doc = " Set takeoff altitude (in meters above ground)."]
753 async fn set_takeoff_altitude(
754 &self,
755 request: tonic::Request<super::SetTakeoffAltitudeRequest>,
756 ) -> Result<tonic::Response<super::SetTakeoffAltitudeResponse>, tonic::Status>;
757 #[doc = ""]
758 #[doc = " Get the vehicle maximum speed (in metres/second)."]
759 async fn get_maximum_speed(
760 &self,
761 request: tonic::Request<super::GetMaximumSpeedRequest>,
762 ) -> Result<tonic::Response<super::GetMaximumSpeedResponse>, tonic::Status>;
763 #[doc = ""]
764 #[doc = " Set vehicle maximum speed (in metres/second)."]
765 async fn set_maximum_speed(
766 &self,
767 request: tonic::Request<super::SetMaximumSpeedRequest>,
768 ) -> Result<tonic::Response<super::SetMaximumSpeedResponse>, tonic::Status>;
769 #[doc = ""]
770 #[doc = " Get the return to launch minimum return altitude (in meters)."]
771 async fn get_return_to_launch_altitude(
772 &self,
773 request: tonic::Request<super::GetReturnToLaunchAltitudeRequest>,
774 ) -> Result<tonic::Response<super::GetReturnToLaunchAltitudeResponse>, tonic::Status>;
775 #[doc = ""]
776 #[doc = " Set the return to launch minimum return altitude (in meters)."]
777 async fn set_return_to_launch_altitude(
778 &self,
779 request: tonic::Request<super::SetReturnToLaunchAltitudeRequest>,
780 ) -> Result<tonic::Response<super::SetReturnToLaunchAltitudeResponse>, tonic::Status>;
781 }
782 #[doc = " Enable simple actions such as arming, taking off, and landing."]
783 #[derive(Debug)]
784 pub struct ActionServiceServer<T: ActionService> {
785 inner: _Inner<T>,
786 accept_compression_encodings: (),
787 send_compression_encodings: (),
788 }
789 struct _Inner<T>(Arc<T>);
790 impl<T: ActionService> ActionServiceServer<T> {
791 pub fn new(inner: T) -> Self {
792 let inner = Arc::new(inner);
793 let inner = _Inner(inner);
794 Self {
795 inner,
796 accept_compression_encodings: Default::default(),
797 send_compression_encodings: Default::default(),
798 }
799 }
800 pub fn with_interceptor<F>(inner: T, interceptor: F) -> InterceptedService<Self, F>
801 where
802 F: tonic::service::Interceptor,
803 {
804 InterceptedService::new(Self::new(inner), interceptor)
805 }
806 }
807 impl<T, B> tonic::codegen::Service<http::Request<B>> for ActionServiceServer<T>
808 where
809 T: ActionService,
810 B: Body + Send + Sync + 'static,
811 B::Error: Into<StdError> + Send + 'static,
812 {
813 type Response = http::Response<tonic::body::BoxBody>;
814 type Error = Never;
815 type Future = BoxFuture<Self::Response, Self::Error>;
816 fn poll_ready(&mut self, _cx: &mut Context<'_>) -> Poll<Result<(), Self::Error>> {
817 Poll::Ready(Ok(()))
818 }
819 fn call(&mut self, req: http::Request<B>) -> Self::Future {
820 let inner = self.inner.clone();
821 match req.uri().path() {
822 "/mavsdk.rpc.action.ActionService/Arm" => {
823 #[allow(non_camel_case_types)]
824 struct ArmSvc<T: ActionService>(pub Arc<T>);
825 impl<T: ActionService> tonic::server::UnaryService<super::ArmRequest> for ArmSvc<T> {
826 type Response = super::ArmResponse;
827 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
828 fn call(
829 &mut self,
830 request: tonic::Request<super::ArmRequest>,
831 ) -> Self::Future {
832 let inner = self.0.clone();
833 let fut = async move { (*inner).arm(request).await };
834 Box::pin(fut)
835 }
836 }
837 let accept_compression_encodings = self.accept_compression_encodings;
838 let send_compression_encodings = self.send_compression_encodings;
839 let inner = self.inner.clone();
840 let fut = async move {
841 let inner = inner.0;
842 let method = ArmSvc(inner);
843 let codec = tonic::codec::ProstCodec::default();
844 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
845 accept_compression_encodings,
846 send_compression_encodings,
847 );
848 let res = grpc.unary(method, req).await;
849 Ok(res)
850 };
851 Box::pin(fut)
852 }
853 "/mavsdk.rpc.action.ActionService/Disarm" => {
854 #[allow(non_camel_case_types)]
855 struct DisarmSvc<T: ActionService>(pub Arc<T>);
856 impl<T: ActionService> tonic::server::UnaryService<super::DisarmRequest> for DisarmSvc<T> {
857 type Response = super::DisarmResponse;
858 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
859 fn call(
860 &mut self,
861 request: tonic::Request<super::DisarmRequest>,
862 ) -> Self::Future {
863 let inner = self.0.clone();
864 let fut = async move { (*inner).disarm(request).await };
865 Box::pin(fut)
866 }
867 }
868 let accept_compression_encodings = self.accept_compression_encodings;
869 let send_compression_encodings = self.send_compression_encodings;
870 let inner = self.inner.clone();
871 let fut = async move {
872 let inner = inner.0;
873 let method = DisarmSvc(inner);
874 let codec = tonic::codec::ProstCodec::default();
875 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
876 accept_compression_encodings,
877 send_compression_encodings,
878 );
879 let res = grpc.unary(method, req).await;
880 Ok(res)
881 };
882 Box::pin(fut)
883 }
884 "/mavsdk.rpc.action.ActionService/Takeoff" => {
885 #[allow(non_camel_case_types)]
886 struct TakeoffSvc<T: ActionService>(pub Arc<T>);
887 impl<T: ActionService> tonic::server::UnaryService<super::TakeoffRequest> for TakeoffSvc<T> {
888 type Response = super::TakeoffResponse;
889 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
890 fn call(
891 &mut self,
892 request: tonic::Request<super::TakeoffRequest>,
893 ) -> Self::Future {
894 let inner = self.0.clone();
895 let fut = async move { (*inner).takeoff(request).await };
896 Box::pin(fut)
897 }
898 }
899 let accept_compression_encodings = self.accept_compression_encodings;
900 let send_compression_encodings = self.send_compression_encodings;
901 let inner = self.inner.clone();
902 let fut = async move {
903 let inner = inner.0;
904 let method = TakeoffSvc(inner);
905 let codec = tonic::codec::ProstCodec::default();
906 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
907 accept_compression_encodings,
908 send_compression_encodings,
909 );
910 let res = grpc.unary(method, req).await;
911 Ok(res)
912 };
913 Box::pin(fut)
914 }
915 "/mavsdk.rpc.action.ActionService/Land" => {
916 #[allow(non_camel_case_types)]
917 struct LandSvc<T: ActionService>(pub Arc<T>);
918 impl<T: ActionService> tonic::server::UnaryService<super::LandRequest> for LandSvc<T> {
919 type Response = super::LandResponse;
920 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
921 fn call(
922 &mut self,
923 request: tonic::Request<super::LandRequest>,
924 ) -> Self::Future {
925 let inner = self.0.clone();
926 let fut = async move { (*inner).land(request).await };
927 Box::pin(fut)
928 }
929 }
930 let accept_compression_encodings = self.accept_compression_encodings;
931 let send_compression_encodings = self.send_compression_encodings;
932 let inner = self.inner.clone();
933 let fut = async move {
934 let inner = inner.0;
935 let method = LandSvc(inner);
936 let codec = tonic::codec::ProstCodec::default();
937 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
938 accept_compression_encodings,
939 send_compression_encodings,
940 );
941 let res = grpc.unary(method, req).await;
942 Ok(res)
943 };
944 Box::pin(fut)
945 }
946 "/mavsdk.rpc.action.ActionService/Reboot" => {
947 #[allow(non_camel_case_types)]
948 struct RebootSvc<T: ActionService>(pub Arc<T>);
949 impl<T: ActionService> tonic::server::UnaryService<super::RebootRequest> for RebootSvc<T> {
950 type Response = super::RebootResponse;
951 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
952 fn call(
953 &mut self,
954 request: tonic::Request<super::RebootRequest>,
955 ) -> Self::Future {
956 let inner = self.0.clone();
957 let fut = async move { (*inner).reboot(request).await };
958 Box::pin(fut)
959 }
960 }
961 let accept_compression_encodings = self.accept_compression_encodings;
962 let send_compression_encodings = self.send_compression_encodings;
963 let inner = self.inner.clone();
964 let fut = async move {
965 let inner = inner.0;
966 let method = RebootSvc(inner);
967 let codec = tonic::codec::ProstCodec::default();
968 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
969 accept_compression_encodings,
970 send_compression_encodings,
971 );
972 let res = grpc.unary(method, req).await;
973 Ok(res)
974 };
975 Box::pin(fut)
976 }
977 "/mavsdk.rpc.action.ActionService/Shutdown" => {
978 #[allow(non_camel_case_types)]
979 struct ShutdownSvc<T: ActionService>(pub Arc<T>);
980 impl<T: ActionService> tonic::server::UnaryService<super::ShutdownRequest> for ShutdownSvc<T> {
981 type Response = super::ShutdownResponse;
982 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
983 fn call(
984 &mut self,
985 request: tonic::Request<super::ShutdownRequest>,
986 ) -> Self::Future {
987 let inner = self.0.clone();
988 let fut = async move { (*inner).shutdown(request).await };
989 Box::pin(fut)
990 }
991 }
992 let accept_compression_encodings = self.accept_compression_encodings;
993 let send_compression_encodings = self.send_compression_encodings;
994 let inner = self.inner.clone();
995 let fut = async move {
996 let inner = inner.0;
997 let method = ShutdownSvc(inner);
998 let codec = tonic::codec::ProstCodec::default();
999 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1000 accept_compression_encodings,
1001 send_compression_encodings,
1002 );
1003 let res = grpc.unary(method, req).await;
1004 Ok(res)
1005 };
1006 Box::pin(fut)
1007 }
1008 "/mavsdk.rpc.action.ActionService/Terminate" => {
1009 #[allow(non_camel_case_types)]
1010 struct TerminateSvc<T: ActionService>(pub Arc<T>);
1011 impl<T: ActionService> tonic::server::UnaryService<super::TerminateRequest> for TerminateSvc<T> {
1012 type Response = super::TerminateResponse;
1013 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1014 fn call(
1015 &mut self,
1016 request: tonic::Request<super::TerminateRequest>,
1017 ) -> Self::Future {
1018 let inner = self.0.clone();
1019 let fut = async move { (*inner).terminate(request).await };
1020 Box::pin(fut)
1021 }
1022 }
1023 let accept_compression_encodings = self.accept_compression_encodings;
1024 let send_compression_encodings = self.send_compression_encodings;
1025 let inner = self.inner.clone();
1026 let fut = async move {
1027 let inner = inner.0;
1028 let method = TerminateSvc(inner);
1029 let codec = tonic::codec::ProstCodec::default();
1030 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1031 accept_compression_encodings,
1032 send_compression_encodings,
1033 );
1034 let res = grpc.unary(method, req).await;
1035 Ok(res)
1036 };
1037 Box::pin(fut)
1038 }
1039 "/mavsdk.rpc.action.ActionService/Kill" => {
1040 #[allow(non_camel_case_types)]
1041 struct KillSvc<T: ActionService>(pub Arc<T>);
1042 impl<T: ActionService> tonic::server::UnaryService<super::KillRequest> for KillSvc<T> {
1043 type Response = super::KillResponse;
1044 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1045 fn call(
1046 &mut self,
1047 request: tonic::Request<super::KillRequest>,
1048 ) -> Self::Future {
1049 let inner = self.0.clone();
1050 let fut = async move { (*inner).kill(request).await };
1051 Box::pin(fut)
1052 }
1053 }
1054 let accept_compression_encodings = self.accept_compression_encodings;
1055 let send_compression_encodings = self.send_compression_encodings;
1056 let inner = self.inner.clone();
1057 let fut = async move {
1058 let inner = inner.0;
1059 let method = KillSvc(inner);
1060 let codec = tonic::codec::ProstCodec::default();
1061 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1062 accept_compression_encodings,
1063 send_compression_encodings,
1064 );
1065 let res = grpc.unary(method, req).await;
1066 Ok(res)
1067 };
1068 Box::pin(fut)
1069 }
1070 "/mavsdk.rpc.action.ActionService/ReturnToLaunch" => {
1071 #[allow(non_camel_case_types)]
1072 struct ReturnToLaunchSvc<T: ActionService>(pub Arc<T>);
1073 impl<T: ActionService> tonic::server::UnaryService<super::ReturnToLaunchRequest>
1074 for ReturnToLaunchSvc<T>
1075 {
1076 type Response = super::ReturnToLaunchResponse;
1077 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1078 fn call(
1079 &mut self,
1080 request: tonic::Request<super::ReturnToLaunchRequest>,
1081 ) -> Self::Future {
1082 let inner = self.0.clone();
1083 let fut = async move { (*inner).return_to_launch(request).await };
1084 Box::pin(fut)
1085 }
1086 }
1087 let accept_compression_encodings = self.accept_compression_encodings;
1088 let send_compression_encodings = self.send_compression_encodings;
1089 let inner = self.inner.clone();
1090 let fut = async move {
1091 let inner = inner.0;
1092 let method = ReturnToLaunchSvc(inner);
1093 let codec = tonic::codec::ProstCodec::default();
1094 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1095 accept_compression_encodings,
1096 send_compression_encodings,
1097 );
1098 let res = grpc.unary(method, req).await;
1099 Ok(res)
1100 };
1101 Box::pin(fut)
1102 }
1103 "/mavsdk.rpc.action.ActionService/GotoLocation" => {
1104 #[allow(non_camel_case_types)]
1105 struct GotoLocationSvc<T: ActionService>(pub Arc<T>);
1106 impl<T: ActionService> tonic::server::UnaryService<super::GotoLocationRequest>
1107 for GotoLocationSvc<T>
1108 {
1109 type Response = super::GotoLocationResponse;
1110 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1111 fn call(
1112 &mut self,
1113 request: tonic::Request<super::GotoLocationRequest>,
1114 ) -> Self::Future {
1115 let inner = self.0.clone();
1116 let fut = async move { (*inner).goto_location(request).await };
1117 Box::pin(fut)
1118 }
1119 }
1120 let accept_compression_encodings = self.accept_compression_encodings;
1121 let send_compression_encodings = self.send_compression_encodings;
1122 let inner = self.inner.clone();
1123 let fut = async move {
1124 let inner = inner.0;
1125 let method = GotoLocationSvc(inner);
1126 let codec = tonic::codec::ProstCodec::default();
1127 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1128 accept_compression_encodings,
1129 send_compression_encodings,
1130 );
1131 let res = grpc.unary(method, req).await;
1132 Ok(res)
1133 };
1134 Box::pin(fut)
1135 }
1136 "/mavsdk.rpc.action.ActionService/TransitionToFixedwing" => {
1137 #[allow(non_camel_case_types)]
1138 struct TransitionToFixedwingSvc<T: ActionService>(pub Arc<T>);
1139 impl<T: ActionService>
1140 tonic::server::UnaryService<super::TransitionToFixedwingRequest>
1141 for TransitionToFixedwingSvc<T>
1142 {
1143 type Response = super::TransitionToFixedwingResponse;
1144 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1145 fn call(
1146 &mut self,
1147 request: tonic::Request<super::TransitionToFixedwingRequest>,
1148 ) -> Self::Future {
1149 let inner = self.0.clone();
1150 let fut =
1151 async move { (*inner).transition_to_fixedwing(request).await };
1152 Box::pin(fut)
1153 }
1154 }
1155 let accept_compression_encodings = self.accept_compression_encodings;
1156 let send_compression_encodings = self.send_compression_encodings;
1157 let inner = self.inner.clone();
1158 let fut = async move {
1159 let inner = inner.0;
1160 let method = TransitionToFixedwingSvc(inner);
1161 let codec = tonic::codec::ProstCodec::default();
1162 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1163 accept_compression_encodings,
1164 send_compression_encodings,
1165 );
1166 let res = grpc.unary(method, req).await;
1167 Ok(res)
1168 };
1169 Box::pin(fut)
1170 }
1171 "/mavsdk.rpc.action.ActionService/TransitionToMulticopter" => {
1172 #[allow(non_camel_case_types)]
1173 struct TransitionToMulticopterSvc<T: ActionService>(pub Arc<T>);
1174 impl<T: ActionService>
1175 tonic::server::UnaryService<super::TransitionToMulticopterRequest>
1176 for TransitionToMulticopterSvc<T>
1177 {
1178 type Response = super::TransitionToMulticopterResponse;
1179 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1180 fn call(
1181 &mut self,
1182 request: tonic::Request<super::TransitionToMulticopterRequest>,
1183 ) -> Self::Future {
1184 let inner = self.0.clone();
1185 let fut =
1186 async move { (*inner).transition_to_multicopter(request).await };
1187 Box::pin(fut)
1188 }
1189 }
1190 let accept_compression_encodings = self.accept_compression_encodings;
1191 let send_compression_encodings = self.send_compression_encodings;
1192 let inner = self.inner.clone();
1193 let fut = async move {
1194 let inner = inner.0;
1195 let method = TransitionToMulticopterSvc(inner);
1196 let codec = tonic::codec::ProstCodec::default();
1197 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1198 accept_compression_encodings,
1199 send_compression_encodings,
1200 );
1201 let res = grpc.unary(method, req).await;
1202 Ok(res)
1203 };
1204 Box::pin(fut)
1205 }
1206 "/mavsdk.rpc.action.ActionService/GetTakeoffAltitude" => {
1207 #[allow(non_camel_case_types)]
1208 struct GetTakeoffAltitudeSvc<T: ActionService>(pub Arc<T>);
1209 impl<T: ActionService>
1210 tonic::server::UnaryService<super::GetTakeoffAltitudeRequest>
1211 for GetTakeoffAltitudeSvc<T>
1212 {
1213 type Response = super::GetTakeoffAltitudeResponse;
1214 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1215 fn call(
1216 &mut self,
1217 request: tonic::Request<super::GetTakeoffAltitudeRequest>,
1218 ) -> Self::Future {
1219 let inner = self.0.clone();
1220 let fut = async move { (*inner).get_takeoff_altitude(request).await };
1221 Box::pin(fut)
1222 }
1223 }
1224 let accept_compression_encodings = self.accept_compression_encodings;
1225 let send_compression_encodings = self.send_compression_encodings;
1226 let inner = self.inner.clone();
1227 let fut = async move {
1228 let inner = inner.0;
1229 let method = GetTakeoffAltitudeSvc(inner);
1230 let codec = tonic::codec::ProstCodec::default();
1231 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1232 accept_compression_encodings,
1233 send_compression_encodings,
1234 );
1235 let res = grpc.unary(method, req).await;
1236 Ok(res)
1237 };
1238 Box::pin(fut)
1239 }
1240 "/mavsdk.rpc.action.ActionService/SetTakeoffAltitude" => {
1241 #[allow(non_camel_case_types)]
1242 struct SetTakeoffAltitudeSvc<T: ActionService>(pub Arc<T>);
1243 impl<T: ActionService>
1244 tonic::server::UnaryService<super::SetTakeoffAltitudeRequest>
1245 for SetTakeoffAltitudeSvc<T>
1246 {
1247 type Response = super::SetTakeoffAltitudeResponse;
1248 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1249 fn call(
1250 &mut self,
1251 request: tonic::Request<super::SetTakeoffAltitudeRequest>,
1252 ) -> Self::Future {
1253 let inner = self.0.clone();
1254 let fut = async move { (*inner).set_takeoff_altitude(request).await };
1255 Box::pin(fut)
1256 }
1257 }
1258 let accept_compression_encodings = self.accept_compression_encodings;
1259 let send_compression_encodings = self.send_compression_encodings;
1260 let inner = self.inner.clone();
1261 let fut = async move {
1262 let inner = inner.0;
1263 let method = SetTakeoffAltitudeSvc(inner);
1264 let codec = tonic::codec::ProstCodec::default();
1265 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1266 accept_compression_encodings,
1267 send_compression_encodings,
1268 );
1269 let res = grpc.unary(method, req).await;
1270 Ok(res)
1271 };
1272 Box::pin(fut)
1273 }
1274 "/mavsdk.rpc.action.ActionService/GetMaximumSpeed" => {
1275 #[allow(non_camel_case_types)]
1276 struct GetMaximumSpeedSvc<T: ActionService>(pub Arc<T>);
1277 impl<T: ActionService>
1278 tonic::server::UnaryService<super::GetMaximumSpeedRequest>
1279 for GetMaximumSpeedSvc<T>
1280 {
1281 type Response = super::GetMaximumSpeedResponse;
1282 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1283 fn call(
1284 &mut self,
1285 request: tonic::Request<super::GetMaximumSpeedRequest>,
1286 ) -> Self::Future {
1287 let inner = self.0.clone();
1288 let fut = async move { (*inner).get_maximum_speed(request).await };
1289 Box::pin(fut)
1290 }
1291 }
1292 let accept_compression_encodings = self.accept_compression_encodings;
1293 let send_compression_encodings = self.send_compression_encodings;
1294 let inner = self.inner.clone();
1295 let fut = async move {
1296 let inner = inner.0;
1297 let method = GetMaximumSpeedSvc(inner);
1298 let codec = tonic::codec::ProstCodec::default();
1299 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1300 accept_compression_encodings,
1301 send_compression_encodings,
1302 );
1303 let res = grpc.unary(method, req).await;
1304 Ok(res)
1305 };
1306 Box::pin(fut)
1307 }
1308 "/mavsdk.rpc.action.ActionService/SetMaximumSpeed" => {
1309 #[allow(non_camel_case_types)]
1310 struct SetMaximumSpeedSvc<T: ActionService>(pub Arc<T>);
1311 impl<T: ActionService>
1312 tonic::server::UnaryService<super::SetMaximumSpeedRequest>
1313 for SetMaximumSpeedSvc<T>
1314 {
1315 type Response = super::SetMaximumSpeedResponse;
1316 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1317 fn call(
1318 &mut self,
1319 request: tonic::Request<super::SetMaximumSpeedRequest>,
1320 ) -> Self::Future {
1321 let inner = self.0.clone();
1322 let fut = async move { (*inner).set_maximum_speed(request).await };
1323 Box::pin(fut)
1324 }
1325 }
1326 let accept_compression_encodings = self.accept_compression_encodings;
1327 let send_compression_encodings = self.send_compression_encodings;
1328 let inner = self.inner.clone();
1329 let fut = async move {
1330 let inner = inner.0;
1331 let method = SetMaximumSpeedSvc(inner);
1332 let codec = tonic::codec::ProstCodec::default();
1333 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1334 accept_compression_encodings,
1335 send_compression_encodings,
1336 );
1337 let res = grpc.unary(method, req).await;
1338 Ok(res)
1339 };
1340 Box::pin(fut)
1341 }
1342 "/mavsdk.rpc.action.ActionService/GetReturnToLaunchAltitude" => {
1343 #[allow(non_camel_case_types)]
1344 struct GetReturnToLaunchAltitudeSvc<T: ActionService>(pub Arc<T>);
1345 impl<T: ActionService>
1346 tonic::server::UnaryService<super::GetReturnToLaunchAltitudeRequest>
1347 for GetReturnToLaunchAltitudeSvc<T>
1348 {
1349 type Response = super::GetReturnToLaunchAltitudeResponse;
1350 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1351 fn call(
1352 &mut self,
1353 request: tonic::Request<super::GetReturnToLaunchAltitudeRequest>,
1354 ) -> Self::Future {
1355 let inner = self.0.clone();
1356 let fut = async move {
1357 (*inner).get_return_to_launch_altitude(request).await
1358 };
1359 Box::pin(fut)
1360 }
1361 }
1362 let accept_compression_encodings = self.accept_compression_encodings;
1363 let send_compression_encodings = self.send_compression_encodings;
1364 let inner = self.inner.clone();
1365 let fut = async move {
1366 let inner = inner.0;
1367 let method = GetReturnToLaunchAltitudeSvc(inner);
1368 let codec = tonic::codec::ProstCodec::default();
1369 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1370 accept_compression_encodings,
1371 send_compression_encodings,
1372 );
1373 let res = grpc.unary(method, req).await;
1374 Ok(res)
1375 };
1376 Box::pin(fut)
1377 }
1378 "/mavsdk.rpc.action.ActionService/SetReturnToLaunchAltitude" => {
1379 #[allow(non_camel_case_types)]
1380 struct SetReturnToLaunchAltitudeSvc<T: ActionService>(pub Arc<T>);
1381 impl<T: ActionService>
1382 tonic::server::UnaryService<super::SetReturnToLaunchAltitudeRequest>
1383 for SetReturnToLaunchAltitudeSvc<T>
1384 {
1385 type Response = super::SetReturnToLaunchAltitudeResponse;
1386 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
1387 fn call(
1388 &mut self,
1389 request: tonic::Request<super::SetReturnToLaunchAltitudeRequest>,
1390 ) -> Self::Future {
1391 let inner = self.0.clone();
1392 let fut = async move {
1393 (*inner).set_return_to_launch_altitude(request).await
1394 };
1395 Box::pin(fut)
1396 }
1397 }
1398 let accept_compression_encodings = self.accept_compression_encodings;
1399 let send_compression_encodings = self.send_compression_encodings;
1400 let inner = self.inner.clone();
1401 let fut = async move {
1402 let inner = inner.0;
1403 let method = SetReturnToLaunchAltitudeSvc(inner);
1404 let codec = tonic::codec::ProstCodec::default();
1405 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
1406 accept_compression_encodings,
1407 send_compression_encodings,
1408 );
1409 let res = grpc.unary(method, req).await;
1410 Ok(res)
1411 };
1412 Box::pin(fut)
1413 }
1414 _ => Box::pin(async move {
1415 Ok(http::Response::builder()
1416 .status(200)
1417 .header("grpc-status", "12")
1418 .header("content-type", "application/grpc")
1419 .body(empty_body())
1420 .unwrap())
1421 }),
1422 }
1423 }
1424 }
1425 impl<T: ActionService> Clone for ActionServiceServer<T> {
1426 fn clone(&self) -> Self {
1427 let inner = self.inner.clone();
1428 Self {
1429 inner,
1430 accept_compression_encodings: self.accept_compression_encodings,
1431 send_compression_encodings: self.send_compression_encodings,
1432 }
1433 }
1434 }
1435 impl<T: ActionService> Clone for _Inner<T> {
1436 fn clone(&self) -> Self {
1437 Self(self.0.clone())
1438 }
1439 }
1440 impl<T: std::fmt::Debug> std::fmt::Debug for _Inner<T> {
1441 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
1442 write!(f, "{:?}", self.0)
1443 }
1444 }
1445 impl<T: ActionService> tonic::transport::NamedService for ActionServiceServer<T> {
1446 const NAME: &'static str = "mavsdk.rpc.action.ActionService";
1447 }
1448}