#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetVisionPositionEstimateRequest {
#[prost(message, optional, tag = "1")]
pub vision_position_estimate: ::core::option::Option<VisionPositionEstimate>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetVisionPositionEstimateResponse {
#[prost(message, optional, tag = "1")]
pub mocap_result: ::core::option::Option<MocapResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetAttitudePositionMocapRequest {
#[prost(message, optional, tag = "1")]
pub attitude_position_mocap: ::core::option::Option<AttitudePositionMocap>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetAttitudePositionMocapResponse {
#[prost(message, optional, tag = "1")]
pub mocap_result: ::core::option::Option<MocapResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetOdometryRequest {
#[prost(message, optional, tag = "1")]
pub odometry: ::core::option::Option<Odometry>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SetOdometryResponse {
#[prost(message, optional, tag = "1")]
pub mocap_result: ::core::option::Option<MocapResult>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct PositionBody {
#[prost(float, tag = "1")]
pub x_m: f32,
#[prost(float, tag = "2")]
pub y_m: f32,
#[prost(float, tag = "3")]
pub z_m: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AngleBody {
#[prost(float, tag = "1")]
pub roll_rad: f32,
#[prost(float, tag = "2")]
pub pitch_rad: f32,
#[prost(float, tag = "3")]
pub yaw_rad: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct SpeedBody {
#[prost(float, tag = "1")]
pub x_m_s: f32,
#[prost(float, tag = "2")]
pub y_m_s: f32,
#[prost(float, tag = "3")]
pub z_m_s: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AngularVelocityBody {
#[prost(float, tag = "1")]
pub roll_rad_s: f32,
#[prost(float, tag = "2")]
pub pitch_rad_s: f32,
#[prost(float, tag = "3")]
pub yaw_rad_s: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Covariance {
#[prost(float, repeated, tag = "1")]
pub covariance_matrix: ::prost::alloc::vec::Vec<f32>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Quaternion {
#[prost(float, tag = "1")]
pub w: f32,
#[prost(float, tag = "2")]
pub x: f32,
#[prost(float, tag = "3")]
pub y: f32,
#[prost(float, tag = "4")]
pub z: f32,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct VisionPositionEstimate {
#[prost(uint64, tag = "1")]
pub time_usec: u64,
#[prost(message, optional, tag = "2")]
pub position_body: ::core::option::Option<PositionBody>,
#[prost(message, optional, tag = "3")]
pub angle_body: ::core::option::Option<AngleBody>,
#[prost(message, optional, tag = "4")]
pub pose_covariance: ::core::option::Option<Covariance>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct AttitudePositionMocap {
#[prost(uint64, tag = "1")]
pub time_usec: u64,
#[prost(message, optional, tag = "2")]
pub q: ::core::option::Option<Quaternion>,
#[prost(message, optional, tag = "3")]
pub position_body: ::core::option::Option<PositionBody>,
#[prost(message, optional, tag = "4")]
pub pose_covariance: ::core::option::Option<Covariance>,
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct Odometry {
#[prost(uint64, tag = "1")]
pub time_usec: u64,
#[prost(enumeration = "odometry::MavFrame", tag = "2")]
pub frame_id: i32,
#[prost(message, optional, tag = "3")]
pub position_body: ::core::option::Option<PositionBody>,
#[prost(message, optional, tag = "4")]
pub q: ::core::option::Option<Quaternion>,
#[prost(message, optional, tag = "5")]
pub speed_body: ::core::option::Option<SpeedBody>,
#[prost(message, optional, tag = "6")]
pub angular_velocity_body: ::core::option::Option<AngularVelocityBody>,
#[prost(message, optional, tag = "7")]
pub pose_covariance: ::core::option::Option<Covariance>,
#[prost(message, optional, tag = "8")]
pub velocity_covariance: ::core::option::Option<Covariance>,
}
pub mod odometry {
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum MavFrame {
MocapNed = 0,
LocalFrd = 1,
}
}
#[derive(Clone, PartialEq, ::prost::Message)]
pub struct MocapResult {
#[prost(enumeration = "mocap_result::Result", tag = "1")]
pub result: i32,
#[prost(string, tag = "2")]
pub result_str: ::prost::alloc::string::String,
}
pub mod mocap_result {
#[derive(Clone, Copy, Debug, PartialEq, Eq, Hash, PartialOrd, Ord, ::prost::Enumeration)]
#[repr(i32)]
pub enum Result {
Unknown = 0,
Success = 1,
NoSystem = 2,
ConnectionError = 3,
InvalidRequestData = 4,
}
}
#[doc = r" Generated client implementations."]
pub mod mocap_service_client {
#![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
use tonic::codegen::*;
#[doc = "*"]
#[doc = " Allows interfacing a vehicle with a motion capture system in"]
#[doc = " order to allow navigation without global positioning sources available"]
#[doc = " (e.g. indoors, or when flying under a bridge. etc.)."]
#[derive(Debug, Clone)]
pub struct MocapServiceClient<T> {
inner: tonic::client::Grpc<T>,
}
impl MocapServiceClient<tonic::transport::Channel> {
#[doc = r" Attempt to create a new client by connecting to a given endpoint."]
pub async fn connect<D>(dst: D) -> Result<Self, tonic::transport::Error>
where
D: std::convert::TryInto<tonic::transport::Endpoint>,
D::Error: Into<StdError>,
{
let conn = tonic::transport::Endpoint::new(dst)?.connect().await?;
Ok(Self::new(conn))
}
}
impl<T> MocapServiceClient<T>
where
T: tonic::client::GrpcService<tonic::body::BoxBody>,
T::ResponseBody: Body + Send + Sync + 'static,
T::Error: Into<StdError>,
<T::ResponseBody as Body>::Error: Into<StdError> + Send,
{
pub fn new(inner: T) -> Self {
let inner = tonic::client::Grpc::new(inner);
Self { inner }
}
pub fn with_interceptor<F>(
inner: T,
interceptor: F,
) -> MocapServiceClient<InterceptedService<T, F>>
where
F: tonic::service::Interceptor,
T: tonic::codegen::Service<
http::Request<tonic::body::BoxBody>,
Response = http::Response<
<T as tonic::client::GrpcService<tonic::body::BoxBody>>::ResponseBody,
>,
>,
<T as tonic::codegen::Service<http::Request<tonic::body::BoxBody>>>::Error:
Into<StdError> + Send + Sync,
{
MocapServiceClient::new(InterceptedService::new(inner, interceptor))
}
#[doc = r" Compress requests with `gzip`."]
#[doc = r""]
#[doc = r" This requires the server to support it otherwise it might respond with an"]
#[doc = r" error."]
pub fn send_gzip(mut self) -> Self {
self.inner = self.inner.send_gzip();
self
}
#[doc = r" Enable decompressing responses with `gzip`."]
pub fn accept_gzip(mut self) -> Self {
self.inner = self.inner.accept_gzip();
self
}
#[doc = " Send Global position/attitude estimate from a vision source."]
pub async fn set_vision_position_estimate(
&mut self,
request: impl tonic::IntoRequest<super::SetVisionPositionEstimateRequest>,
) -> Result<tonic::Response<super::SetVisionPositionEstimateResponse>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Send motion capture attitude and position."]
pub async fn set_attitude_position_mocap(
&mut self,
request: impl tonic::IntoRequest<super::SetAttitudePositionMocapRequest>,
) -> Result<tonic::Response<super::SetAttitudePositionMocapResponse>, tonic::Status>
{
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path = http::uri::PathAndQuery::from_static(
"/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap",
);
self.inner.unary(request.into_request(), path, codec).await
}
#[doc = " Send odometry information with an external interface."]
pub async fn set_odometry(
&mut self,
request: impl tonic::IntoRequest<super::SetOdometryRequest>,
) -> Result<tonic::Response<super::SetOdometryResponse>, tonic::Status> {
self.inner.ready().await.map_err(|e| {
tonic::Status::new(
tonic::Code::Unknown,
format!("Service was not ready: {}", e.into()),
)
})?;
let codec = tonic::codec::ProstCodec::default();
let path =
http::uri::PathAndQuery::from_static("/mavsdk.rpc.mocap.MocapService/SetOdometry");
self.inner.unary(request.into_request(), path, codec).await
}
}
}
#[doc = r" Generated server implementations."]
pub mod mocap_service_server {
#![allow(unused_variables, dead_code, missing_docs, clippy::let_unit_value)]
use tonic::codegen::*;
#[doc = "Generated trait containing gRPC methods that should be implemented for use with MocapServiceServer."]
#[async_trait]
pub trait MocapService: Send + Sync + 'static {
#[doc = " Send Global position/attitude estimate from a vision source."]
async fn set_vision_position_estimate(
&self,
request: tonic::Request<super::SetVisionPositionEstimateRequest>,
) -> Result<tonic::Response<super::SetVisionPositionEstimateResponse>, tonic::Status>;
#[doc = " Send motion capture attitude and position."]
async fn set_attitude_position_mocap(
&self,
request: tonic::Request<super::SetAttitudePositionMocapRequest>,
) -> Result<tonic::Response<super::SetAttitudePositionMocapResponse>, tonic::Status>;
#[doc = " Send odometry information with an external interface."]
async fn set_odometry(
&self,
request: tonic::Request<super::SetOdometryRequest>,
) -> Result<tonic::Response<super::SetOdometryResponse>, tonic::Status>;
}
#[doc = "*"]
#[doc = " Allows interfacing a vehicle with a motion capture system in"]
#[doc = " order to allow navigation without global positioning sources available"]
#[doc = " (e.g. indoors, or when flying under a bridge. etc.)."]
#[derive(Debug)]
pub struct MocapServiceServer<T: MocapService> {
inner: _Inner<T>,
accept_compression_encodings: (),
send_compression_encodings: (),
}
struct _Inner<T>(Arc<T>);
impl<T: MocapService> MocapServiceServer<T> {
pub fn new(inner: T) -> Self {
let inner = Arc::new(inner);
let inner = _Inner(inner);
Self {
inner,
accept_compression_encodings: Default::default(),
send_compression_encodings: Default::default(),
}
}
pub fn with_interceptor<F>(inner: T, interceptor: F) -> InterceptedService<Self, F>
where
F: tonic::service::Interceptor,
{
InterceptedService::new(Self::new(inner), interceptor)
}
}
impl<T, B> tonic::codegen::Service<http::Request<B>> for MocapServiceServer<T>
where
T: MocapService,
B: Body + Send + Sync + 'static,
B::Error: Into<StdError> + Send + 'static,
{
type Response = http::Response<tonic::body::BoxBody>;
type Error = Never;
type Future = BoxFuture<Self::Response, Self::Error>;
fn poll_ready(&mut self, _cx: &mut Context<'_>) -> Poll<Result<(), Self::Error>> {
Poll::Ready(Ok(()))
}
fn call(&mut self, req: http::Request<B>) -> Self::Future {
let inner = self.inner.clone();
match req.uri().path() {
"/mavsdk.rpc.mocap.MocapService/SetVisionPositionEstimate" => {
#[allow(non_camel_case_types)]
struct SetVisionPositionEstimateSvc<T: MocapService>(pub Arc<T>);
impl<T: MocapService>
tonic::server::UnaryService<super::SetVisionPositionEstimateRequest>
for SetVisionPositionEstimateSvc<T>
{
type Response = super::SetVisionPositionEstimateResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetVisionPositionEstimateRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).set_vision_position_estimate(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetVisionPositionEstimateSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.mocap.MocapService/SetAttitudePositionMocap" => {
#[allow(non_camel_case_types)]
struct SetAttitudePositionMocapSvc<T: MocapService>(pub Arc<T>);
impl<T: MocapService>
tonic::server::UnaryService<super::SetAttitudePositionMocapRequest>
for SetAttitudePositionMocapSvc<T>
{
type Response = super::SetAttitudePositionMocapResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetAttitudePositionMocapRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut =
async move { (*inner).set_attitude_position_mocap(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetAttitudePositionMocapSvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
"/mavsdk.rpc.mocap.MocapService/SetOdometry" => {
#[allow(non_camel_case_types)]
struct SetOdometrySvc<T: MocapService>(pub Arc<T>);
impl<T: MocapService> tonic::server::UnaryService<super::SetOdometryRequest> for SetOdometrySvc<T> {
type Response = super::SetOdometryResponse;
type Future = BoxFuture<tonic::Response<Self::Response>, tonic::Status>;
fn call(
&mut self,
request: tonic::Request<super::SetOdometryRequest>,
) -> Self::Future {
let inner = self.0.clone();
let fut = async move { (*inner).set_odometry(request).await };
Box::pin(fut)
}
}
let accept_compression_encodings = self.accept_compression_encodings;
let send_compression_encodings = self.send_compression_encodings;
let inner = self.inner.clone();
let fut = async move {
let inner = inner.0;
let method = SetOdometrySvc(inner);
let codec = tonic::codec::ProstCodec::default();
let mut grpc = tonic::server::Grpc::new(codec).apply_compression_config(
accept_compression_encodings,
send_compression_encodings,
);
let res = grpc.unary(method, req).await;
Ok(res)
};
Box::pin(fut)
}
_ => Box::pin(async move {
Ok(http::Response::builder()
.status(200)
.header("grpc-status", "12")
.header("content-type", "application/grpc")
.body(empty_body())
.unwrap())
}),
}
}
}
impl<T: MocapService> Clone for MocapServiceServer<T> {
fn clone(&self) -> Self {
let inner = self.inner.clone();
Self {
inner,
accept_compression_encodings: self.accept_compression_encodings,
send_compression_encodings: self.send_compression_encodings,
}
}
}
impl<T: MocapService> Clone for _Inner<T> {
fn clone(&self) -> Self {
Self(self.0.clone())
}
}
impl<T: std::fmt::Debug> std::fmt::Debug for _Inner<T> {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
write!(f, "{:?}", self.0)
}
}
impl<T: MocapService> tonic::transport::NamedService for MocapServiceServer<T> {
const NAME: &'static str = "mavsdk.rpc.mocap.MocapService";
}
}