1#[derive(Clone, PartialEq, ::prost::Message)]
2pub struct SetVisionPositionEstimateRequest {
3 #[prost(message, optional, tag = "1")]
5 pub vision_position_estimate: ::core::option::Option<VisionPositionEstimate>,
6}
7#[derive(Clone, PartialEq, ::prost::Message)]
8pub struct SetVisionPositionEstimateResponse {
9 #[prost(message, optional, tag = "1")]
10 pub mocap_result: ::core::option::Option<MocapResult>,
11}
12#[derive(Clone, PartialEq, ::prost::Message)]
13pub struct SetAttitudePositionMocapRequest {
14 #[prost(message, optional, tag = "1")]
16 pub attitude_position_mocap: ::core::option::Option<AttitudePositionMocap>,
17}
18#[derive(Clone, PartialEq, ::prost::Message)]
19pub struct SetAttitudePositionMocapResponse {
20 #[prost(message, optional, tag = "1")]
21 pub mocap_result: ::core::option::Option<MocapResult>,
22}
23#[derive(Clone, PartialEq, ::prost::Message)]
24pub struct SetOdometryRequest {
25 #[prost(message, optional, tag = "1")]
27 pub odometry: ::core::option::Option<Odometry>,
28}
29#[derive(Clone, PartialEq, ::prost::Message)]
30pub struct SetOdometryResponse {
31 #[prost(message, optional, tag = "1")]
32 pub mocap_result: ::core::option::Option<MocapResult>,
33}
34#[derive(Clone, PartialEq, ::prost::Message)]
36pub struct PositionBody {
37 #[prost(float, tag = "1")]
39 pub x_m: f32,
40 #[prost(float, tag = "2")]
42 pub y_m: f32,
43 #[prost(float, tag = "3")]
45 pub z_m: f32,
46}
47#[derive(Clone, PartialEq, ::prost::Message)]
49pub struct AngleBody {
50 #[prost(float, tag = "1")]
52 pub roll_rad: f32,
53 #[prost(float, tag = "2")]
55 pub pitch_rad: f32,
56 #[prost(float, tag = "3")]
58 pub yaw_rad: f32,
59}
60#[derive(Clone, PartialEq, ::prost::Message)]
62pub struct SpeedBody {
63 #[prost(float, tag = "1")]
65 pub x_m_s: f32,
66 #[prost(float, tag = "2")]
68 pub y_m_s: f32,
69 #[prost(float, tag = "3")]
71 pub z_m_s: f32,
72}
73#[derive(Clone, PartialEq, ::prost::Message)]
75pub struct AngularVelocityBody {
76 #[prost(float, tag = "1")]
78 pub roll_rad_s: f32,
79 #[prost(float, tag = "2")]
81 pub pitch_rad_s: f32,
82 #[prost(float, tag = "3")]
84 pub yaw_rad_s: f32,
85}
86#[derive(Clone, PartialEq, ::prost::Message)]
91pub struct Covariance {
92 #[prost(float, repeated, tag = "1")]
94 pub covariance_matrix: ::prost::alloc::vec::Vec<f32>,
95}
96#[derive(Clone, PartialEq, ::prost::Message)]
106pub struct Quaternion {
107 #[prost(float, tag = "1")]
109 pub w: f32,
110 #[prost(float, tag = "2")]
112 pub x: f32,
113 #[prost(float, tag = "3")]
115 pub y: f32,
116 #[prost(float, tag = "4")]
118 pub z: f32,
119}
120#[derive(Clone, PartialEq, ::prost::Message)]
122pub struct VisionPositionEstimate {
123 #[prost(uint64, tag = "1")]
125 pub time_usec: u64,
126 #[prost(message, optional, tag = "2")]
128 pub position_body: ::core::option::Option<PositionBody>,
129 #[prost(message, optional, tag = "3")]
131 pub angle_body: ::core::option::Option<AngleBody>,
132 #[prost(message, optional, tag = "4")]
134 pub pose_covariance: ::core::option::Option<Covariance>,
135}
136#[derive(Clone, PartialEq, ::prost::Message)]
138pub struct AttitudePositionMocap {
139 #[prost(uint64, tag = "1")]
141 pub time_usec: u64,
142 #[prost(message, optional, tag = "2")]
144 pub q: ::core::option::Option<Quaternion>,
145 #[prost(message, optional, tag = "3")]
147 pub position_body: ::core::option::Option<PositionBody>,
148 #[prost(message, optional, tag = "4")]
150 pub pose_covariance: ::core::option::Option<Covariance>,
151}
152#[derive(Clone, PartialEq, ::prost::Message)]
154pub struct Odometry {
155 #[prost(uint64, tag = "1")]
157 pub time_usec: u64,
158 #[prost(enumeration = "odometry::MavFrame", tag = "2")]
160 pub frame_id: i32,
161 #[prost(message, optional, tag = "3")]
163 pub position_body: ::core::option::Option<PositionBody>,
164 #[prost(message, optional, tag = "4")]
166 pub q: ::core::option::Option<Quaternion>,
167 #[prost(message, optional, tag = "5")]
169 pub speed_body: ::core::option::Option<SpeedBody>,
170 #[prost(message, optional, tag = "6")]
172 pub angular_velocity_body: ::core::option::Option<AngularVelocityBody>,
173 #[prost(message, optional, tag = "7")]
175 pub pose_covariance: ::core::option::Option<Covariance>,
176 #[prost(message, optional, tag = "8")]
178 pub velocity_covariance: ::core::option::Option<Covariance>,
179}
180pub mod odometry {
182 #[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
184 #[repr(i32)]
185 pub enum MavFrame {
186 MocapNed = 0,
188 LocalFrd = 1,
190 }
191}
192#[derive(Clone, PartialEq, ::prost::Message)]
194pub struct MocapResult {
195 #[prost(enumeration = "mocap_result::Result", tag = "1")]
197 pub result: i32,
198 #[prost(string, tag = "2")]
200 pub result_str: ::prost::alloc::string::String,
201}
202pub mod mocap_result {
204 #[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
206 #[repr(i32)]
207 pub enum Result {
208 Unknown = 0,
210 Success = 1,
212 NoSystem = 2,
214 ConnectionError = 3,
216 InvalidRequestData = 4,
218 }
219}
220#[doc = r" Generated client implementations."]
221pub mod mocap_service_client {
222 #![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
223 use tonic::codegen::*;
224 #[doc = "*"]
225 #[doc = " Allows interfacing a vehicle with a motion capture system in"]
226 #[doc = " order to allow navigation without global positioning sources available"]
227 #[doc = " (e.g. indoors, or when flying under a bridge. etc.)."]
228 #[derive(Debug, Clone)]
229 pub struct MocapServiceClient<T> {
230 inner: tonic::client::Grpc<T>,
231 }
232 impl MocapServiceClient<tonic::transport::Channel> {
233 #[doc = r" Attempt to create a new client by connecting to a given endpoint."]
234 pub async fn connect<D>(dst: D) -> Result<Self, tonic::transport::Error>
235 where
236 D: std::convert::TryInto<tonic::transport::Endpoint>,
237 D::Error: Into<StdError>,
238 {
239 let conn = tonic::transport::Endpoint::new(dst)?.connect().await?;
240 Ok(Self::new(conn))
241 }
242 }
243 impl<T> MocapServiceClient<T>
244 where
245 T: tonic::client::GrpcService<tonic::body::BoxBody>,
246 T::ResponseBody: Body + Send + Sync + 'static,
247 T::Error: Into<StdError>,
248 <T::ResponseBody as Body>::Error: Into<StdError> + Send,
249 {
250 pub fn new(inner: T) -> Self {
251 let inner = tonic::client::Grpc::new(inner);
252 Self { inner }
253 }
254 pub fn with_interceptor<F>(
255 inner: T,
256 interceptor: F,
257 ) -> MocapServiceClient<InterceptedService<T, F>>
258 where
259 F: tonic::service::Interceptor,
260 T: tonic::codegen::Service<
261 http::Request<tonic::body::BoxBody>,
262 Response = http::Response<
263 <T as tonic::client::GrpcService<tonic::body::BoxBody>>::ResponseBody,
264 >,
265 >,
266 <T as tonic::codegen::Service<http::Request<tonic::body::BoxBody>>>::Error:
267 Into<StdError> + Send + Sync,
268 {
269 MocapServiceClient::new(InterceptedService::new(inner, interceptor))
270 }
271 #[doc = r" Compress requests with `gzip`."]
272 #[doc = r""]
273 #[doc = r" This requires the server to support it otherwise it might respond with an"]
274 #[doc = r" error."]
275 pub fn send_gzip(mut self) -> Self {
276 self.inner = self.inner.send_gzip();
277 self
278 }
279 #[doc = r" Enable decompressing responses with `gzip`."]
280 pub fn accept_gzip(mut self) -> Self {
281 self.inner = self.inner.accept_gzip();
282 self
283 }
284 #[doc = " Send Global position/attitude estimate from a vision source."]
285 pub async fn set_vision_position_estimate(
286 &mut self,
287 request: impl tonic::IntoRequest<super::SetVisionPositionEstimateRequest>,
288 ) -> Result<tonic::Response<super::SetVisionPositionEstimateResponse>, tonic::Status>
289 {
290 self.inner.ready().await.map_err(|e| {
291 tonic::Status::new(
292 tonic::Code::Unknown,
293 format!("Service was not ready: {}", e.into()),
294 )
295 })?;
296 let codec = tonic::codec::ProstCodec::default();
297 let path = http::uri::PathAndQuery::from_static(
298 "/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate",
299 );
300 self.inner.unary(request.into_request(), path, codec).await
301 }
302 #[doc = " Send motion capture attitude and position."]
303 pub async fn set_attitude_position_mocap(
304 &mut self,
305 request: impl tonic::IntoRequest<super::SetAttitudePositionMocapRequest>,
306 ) -> Result<tonic::Response<super::SetAttitudePositionMocapResponse>, tonic::Status>
307 {
308 self.inner.ready().await.map_err(|e| {
309 tonic::Status::new(
310 tonic::Code::Unknown,
311 format!("Service was not ready: {}", e.into()),
312 )
313 })?;
314 let codec = tonic::codec::ProstCodec::default();
315 let path = http::uri::PathAndQuery::from_static(
316 "/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap",
317 );
318 self.inner.unary(request.into_request(), path, codec).await
319 }
320 #[doc = " Send odometry information with an external interface."]
321 pub async fn set_odometry(
322 &mut self,
323 request: impl tonic::IntoRequest<super::SetOdometryRequest>,
324 ) -> Result<tonic::Response<super::SetOdometryResponse>, tonic::Status> {
325 self.inner.ready().await.map_err(|e| {
326 tonic::Status::new(
327 tonic::Code::Unknown,
328 format!("Service was not ready: {}", e.into()),
329 )
330 })?;
331 let codec = tonic::codec::ProstCodec::default();
332 let path =
333 http::uri::PathAndQuery::from_static("/mavsdk.rpc.mocap.MocapService/SetOdometry");
334 self.inner.unary(request.into_request(), path, codec).await
335 }
336 }
337}
338#[doc = r" Generated server implementations."]
339pub mod mocap_service_server {
340 #![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
341 use tonic::codegen::*;
342 #[doc = "Generated trait containing gRPC methods that should be implemented for use with MocapServiceServer."]
343 #[async_trait]
344 pub trait MocapService: Send + Sync + 'static {
345 #[doc = " Send Global position/attitude estimate from a vision source."]
346 async fn set_vision_position_estimate(
347 &self,
348 request: tonic::Request<super::SetVisionPositionEstimateRequest>,
349 ) -> Result<tonic::Response<super::SetVisionPositionEstimateResponse>, tonic::Status>;
350 #[doc = " Send motion capture attitude and position."]
351 async fn set_attitude_position_mocap(
352 &self,
353 request: tonic::Request<super::SetAttitudePositionMocapRequest>,
354 ) -> Result<tonic::Response<super::SetAttitudePositionMocapResponse>, tonic::Status>;
355 #[doc = " Send odometry information with an external interface."]
356 async fn set_odometry(
357 &self,
358 request: tonic::Request<super::SetOdometryRequest>,
359 ) -> Result<tonic::Response<super::SetOdometryResponse>, tonic::Status>;
360 }
361 #[doc = "*"]
362 #[doc = " Allows interfacing a vehicle with a motion capture system in"]
363 #[doc = " order to allow navigation without global positioning sources available"]
364 #[doc = " (e.g. indoors, or when flying under a bridge. etc.)."]
365 #[derive(Debug)]
366 pub struct MocapServiceServer<T: MocapService> {
367 inner: _Inner<T>,
368 accept_compression_encodings: (),
369 send_compression_encodings: (),
370 }
371 struct _Inner<T>(Arc<T>);
372 impl<T: MocapService> MocapServiceServer<T> {
373 pub fn new(inner: T) -> Self {
374 let inner = Arc::new(inner);
375 let inner = _Inner(inner);
376 Self {
377 inner,
378 accept_compression_encodings: Default::default(),
379 send_compression_encodings: Default::default(),
380 }
381 }
382 pub fn with_interceptor<F>(inner: T, interceptor: F) -> InterceptedService<Self, F>
383 where
384 F: tonic::service::Interceptor,
385 {
386 InterceptedService::new(Self::new(inner), interceptor)
387 }
388 }
389 impl<T, B> tonic::codegen::Service<http::Request<B>> for MocapServiceServer<T>
390 where
391 T: MocapService,
392 B: Body + Send + Sync + 'static,
393 B::Error: Into<StdError> + Send + 'static,
394 {
395 type Response = http::Response<tonic::body::BoxBody>;
396 type Error = Never;
397 type Future = BoxFuture<Self::Response, Self::Error>;
398 fn poll_ready(&mut self, _cx: &mut Context<'_>) -> Poll<Result<(), Self::Error>> {
399 Poll::Ready(Ok(()))
400 }
401 fn call(&mut self, req: http::Request<B>) -> Self::Future {
402 let inner = self.inner.clone();
403 match req.uri().path() {
404 "/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate" => {
405 #[allow(non_camel_case_types)]
406 struct SetVisionPositionEstimateSvc<T: MocapService>(pub Arc<T>);
407 impl<T: MocapService>
408 tonic::server::UnaryService<super::SetVisionPositionEstimateRequest>
409 for SetVisionPositionEstimateSvc<T>
410 {
411 type Response = super::SetVisionPositionEstimateResponse;
412 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
413 fn call(
414 &mut self,
415 request: tonic::Request<super::SetVisionPositionEstimateRequest>,
416 ) -> Self::Future {
417 let inner = self.0.clone();
418 let fut =
419 async move { (*inner).set_vision_position_estimate(request).await };
420 Box::pin(fut)
421 }
422 }
423 let accept_compression_encodings = self.accept_compression_encodings;
424 let send_compression_encodings = self.send_compression_encodings;
425 let inner = self.inner.clone();
426 let fut = async move {
427 let inner = inner.0;
428 let method = SetVisionPositionEstimateSvc(inner);
429 let codec = tonic::codec::ProstCodec::default();
430 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
431 accept_compression_encodings,
432 send_compression_encodings,
433 );
434 let res = grpc.unary(method, req).await;
435 Ok(res)
436 };
437 Box::pin(fut)
438 }
439 "/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap" => {
440 #[allow(non_camel_case_types)]
441 struct SetAttitudePositionMocapSvc<T: MocapService>(pub Arc<T>);
442 impl<T: MocapService>
443 tonic::server::UnaryService<super::SetAttitudePositionMocapRequest>
444 for SetAttitudePositionMocapSvc<T>
445 {
446 type Response = super::SetAttitudePositionMocapResponse;
447 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
448 fn call(
449 &mut self,
450 request: tonic::Request<super::SetAttitudePositionMocapRequest>,
451 ) -> Self::Future {
452 let inner = self.0.clone();
453 let fut =
454 async move { (*inner).set_attitude_position_mocap(request).await };
455 Box::pin(fut)
456 }
457 }
458 let accept_compression_encodings = self.accept_compression_encodings;
459 let send_compression_encodings = self.send_compression_encodings;
460 let inner = self.inner.clone();
461 let fut = async move {
462 let inner = inner.0;
463 let method = SetAttitudePositionMocapSvc(inner);
464 let codec = tonic::codec::ProstCodec::default();
465 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
466 accept_compression_encodings,
467 send_compression_encodings,
468 );
469 let res = grpc.unary(method, req).await;
470 Ok(res)
471 };
472 Box::pin(fut)
473 }
474 "/mavsdk.rpc.mocap.MocapService/SetOdometry" => {
475 #[allow(non_camel_case_types)]
476 struct SetOdometrySvc<T: MocapService>(pub Arc<T>);
477 impl<T: MocapService> tonic::server::UnaryService<super::SetOdometryRequest> for SetOdometrySvc<T> {
478 type Response = super::SetOdometryResponse;
479 type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
480 fn call(
481 &mut self,
482 request: tonic::Request<super::SetOdometryRequest>,
483 ) -> Self::Future {
484 let inner = self.0.clone();
485 let fut = async move { (*inner).set_odometry(request).await };
486 Box::pin(fut)
487 }
488 }
489 let accept_compression_encodings = self.accept_compression_encodings;
490 let send_compression_encodings = self.send_compression_encodings;
491 let inner = self.inner.clone();
492 let fut = async move {
493 let inner = inner.0;
494 let method = SetOdometrySvc(inner);
495 let codec = tonic::codec::ProstCodec::default();
496 let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
497 accept_compression_encodings,
498 send_compression_encodings,
499 );
500 let res = grpc.unary(method, req).await;
501 Ok(res)
502 };
503 Box::pin(fut)
504 }
505 _ => Box::pin(async move {
506 Ok(http::Response::builder()
507 .status(200)
508 .header("grpc-status", "12")
509 .header("content-type", "application/grpc")
510 .body(empty_body())
511 .unwrap())
512 }),
513 }
514 }
515 }
516 impl<T: MocapService> Clone for MocapServiceServer<T> {
517 fn clone(&self) -> Self {
518 let inner = self.inner.clone();
519 Self {
520 inner,
521 accept_compression_encodings: self.accept_compression_encodings,
522 send_compression_encodings: self.send_compression_encodings,
523 }
524 }
525 }
526 impl<T: MocapService> Clone for _Inner<T> {
527 fn clone(&self) -> Self {
528 Self(self.0.clone())
529 }
530 }
531 impl<T: std::fmt::Debug> std::fmt::Debug for _Inner<T> {
532 fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
533 write!(f, "{:?}", self.0)
534 }
535 }
536 impl<T: MocapService> tonic::transport::NamedService for MocapServiceServer<T> {
537 const NAME: &'static str = "mavsdk.rpc.mocap.MocapService";
538 }
539}