diff --git a/Cargo.lock b/Cargo.lock index 71bd8ff..70e1fef 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -296,6 +296,7 @@ dependencies = [ "bytes", "futures-util", "prost", + "thiserror", "tokio", "tonic", "tonic-build", @@ -585,6 +586,26 @@ dependencies = [ "winapi", ] +[[package]] +name = "thiserror" +version = "1.0.30" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "854babe52e4df1653706b98fcfc05843010039b406875930a70e4d9644e5c417" +dependencies = [ + "thiserror-impl", +] + +[[package]] +name = "thiserror-impl" +version = "1.0.30" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "aa32fd3f627f367fe16f893e2597ae3c05020f8bba2666a4e6ea73d377e5714b" +dependencies = [ + "proc-macro2", + "quote", + "syn", +] + [[package]] name = "tokio" version = "1.12.0" diff --git a/Cargo.toml b/Cargo.toml index 0989dac..704b61a 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -10,6 +10,7 @@ bytes = "1.1.0" prost = "0.8.0" futures-util = { version = "0.3", default-features = false } +thiserror = "1.0.30" [dev-dependencies] tokio = { version = "1.12.0", features = ["rt-multi-thread", "macros", "time"] } diff --git a/examples/info.rs b/examples/info.rs index efbdfea..9fefd00 100644 --- a/examples/info.rs +++ b/examples/info.rs @@ -1,4 +1,4 @@ -use libmavsdk::{info, RequestError, System}; +use libmavsdk::System; use std::io::{self, Write}; #[tokio::main] @@ -24,12 +24,6 @@ async fn main() { match system.info.get_version().await { Ok(v) => println!("Version received: {:?}", v), - Err(RequestError::MavErr(info::InfoError::Unknown(s))) => { - println!("Unknown MAVLink error ({:?})", s); - } - Err(RequestError::MavErr(info::InfoError::InformationNotReceivedYet(s))) => { - println!("{}", s); - } - Err(RequestError::RpcErr(rpc_err)) => println!("RPC error: {:?}", rpc_err), + Err(e) => println!("{}", e), }; } diff --git a/examples/mocap.rs b/examples/mocap.rs index 865c7c9..358da52 100644 --- a/examples/mocap.rs +++ b/examples/mocap.rs @@ -1,4 +1,4 @@ -use libmavsdk::{mocap, RequestError, System}; +use libmavsdk::{mocap, System}; use std::io::{self, Write}; use std::time::Duration; @@ -34,10 +34,7 @@ async fn main() { .set_vision_position_estimate(vision_position_estimate.clone()) .await { - match error { - RequestError::MavErr(mav_err) => println!("MAVLink error: {:?}", mav_err), - RequestError::RpcErr(rpc_err) => println!("RPC error: {:?}", rpc_err.message()), - } + println!("{}", error); return; }; counter -= 1; diff --git a/src/generated/info/mod.rs b/src/generated/info/mod.rs index 5076537..ab6f195 100644 --- a/src/generated/info/mod.rs +++ b/src/generated/info/mod.rs @@ -1,5 +1,5 @@ use super::super::FromRpcResponse; -use super::super::RequestError::{MavErr, RpcErr}; +use super::super::RequestError; use super::super::RequestResult; use super::super::TonicResult; @@ -45,9 +45,11 @@ impl From<&pb::Version> for Version { } } -#[derive(PartialEq, Clone, Debug)] +#[derive(PartialEq, Clone, Debug, thiserror::Error)] pub enum InfoError { + #[error("Unknown error: {0}")] Unknown(String), + #[error("Information not yet received: {0}")] InformationNotReceivedYet(String), } @@ -55,15 +57,15 @@ pub type GetVersionResult = RequestResult; impl FromRpcResponse for GetVersionResult { fn from_rpc_response(rpc_get_version_response: TonicResult) -> Self { - let get_version_response = rpc_get_version_response.map_err(RpcErr)?.into_inner(); + let get_version_response = rpc_get_version_response?.into_inner(); - let rpc_info_result = get_version_response - .info_result - .ok_or_else(|| MavErr(InfoError::Unknown("InfoResult does not received".into())))?; + let rpc_info_result = get_version_response.info_result.ok_or_else(|| { + RequestError::Mav(InfoError::Unknown("InfoResult does not received".into())) + })?; let info_result = pb::info_result::Result::from_i32(rpc_info_result.result).ok_or_else(|| { - MavErr(InfoError::Unknown( + RequestError::Mav(InfoError::Unknown( "Unsupported InfoResult.result value".into(), )) })?; @@ -71,14 +73,14 @@ impl FromRpcResponse for GetVersionResult { match info_result { pb::info_result::Result::Success => match get_version_response.version { Some(ref rpc_version) => Ok(Version::from(rpc_version)), - None => Err(MavErr(InfoError::Unknown( + None => Err(RequestError::Mav(InfoError::Unknown( "Version does not received".into(), ))), }, - pb::info_result::Result::Unknown => { - Err(MavErr(InfoError::Unknown(rpc_info_result.result_str))) - } - pb::info_result::Result::InformationNotReceivedYet => Err(MavErr( + pb::info_result::Result::Unknown => Err(RequestError::Mav(InfoError::Unknown( + rpc_info_result.result_str, + ))), + pb::info_result::Result::InformationNotReceivedYet => Err(RequestError::Mav( InfoError::InformationNotReceivedYet(rpc_info_result.result_str), )), } diff --git a/src/generated/mocap/mod.rs b/src/generated/mocap/mod.rs index 8a43226..0d4e5eb 100644 --- a/src/generated/mocap/mod.rs +++ b/src/generated/mocap/mod.rs @@ -1,5 +1,5 @@ use super::super::FromRpcResponse; -use super::super::RequestError::{MavErr, RpcErr}; +use super::super::RequestError; use super::super::RequestResult; use super::super::TonicResult; use std::convert::Into; @@ -225,15 +225,19 @@ impl Into for Quaternion { } } -#[derive(PartialEq, Clone, Debug)] +#[derive(PartialEq, Clone, Debug, thiserror::Error)] pub enum MocapError { /// Unknown error + #[error("Unknown error: {0}")] Unknown(String), /// No system is connected + #[error("No system is connected: {0}")] NoSystem(String), /// Connection error + #[error("Connection error: {0}")] ConnectionError(String), /// Invalid request data + #[error("Invalid request: {0}")] InvalidRequestData(String), } @@ -245,31 +249,32 @@ impl FromRpcResponse for SetVisionPositio pb::SetVisionPositionEstimateResponse, >, ) -> Self { - let rpc_mocap_result = rpc_set_vision_position_estimate_response - .map_err(RpcErr)? + let rpc_mocap_result = rpc_set_vision_position_estimate_response? .into_inner() .mocap_result - .ok_or_else(|| MavErr(MocapError::Unknown("MocapResult does not received".into())))?; + .ok_or_else(|| { + RequestError::Mav(MocapError::Unknown("MocapResult does not received".into())) + })?; let mocap_result = pb::mocap_result::Result::from_i32(rpc_mocap_result.result).ok_or_else(|| { - MavErr(MocapError::Unknown( + RequestError::Mav(MocapError::Unknown( "Unsupported MocapResult.result value".into(), )) })?; match mocap_result { pb::mocap_result::Result::Success => Ok(()), - pb::mocap_result::Result::Unknown => { - Err(MavErr(MocapError::Unknown(rpc_mocap_result.result_str))) - } - pb::mocap_result::Result::NoSystem => { - Err(MavErr(MocapError::NoSystem(rpc_mocap_result.result_str))) - } - pb::mocap_result::Result::ConnectionError => Err(MavErr(MocapError::ConnectionError( + pb::mocap_result::Result::Unknown => Err(RequestError::Mav(MocapError::Unknown( + rpc_mocap_result.result_str, + ))), + pb::mocap_result::Result::NoSystem => Err(RequestError::Mav(MocapError::NoSystem( rpc_mocap_result.result_str, ))), - pb::mocap_result::Result::InvalidRequestData => Err(MavErr( + pb::mocap_result::Result::ConnectionError => Err(RequestError::Mav( + MocapError::ConnectionError(rpc_mocap_result.result_str), + )), + pb::mocap_result::Result::InvalidRequestData => Err(RequestError::Mav( MocapError::InvalidRequestData(rpc_mocap_result.result_str), )), } diff --git a/src/generated/telemetry/mod.rs b/src/generated/telemetry/mod.rs index 3c9f061..addb3ab 100644 --- a/src/generated/telemetry/mod.rs +++ b/src/generated/telemetry/mod.rs @@ -1,4 +1,4 @@ -use super::super::RequestError::{MavErr, RpcErr}; +use super::super::RequestError; use super::super::RequestResult; use futures_util::stream::{Stream, StreamExt}; use std::pin::Pin; @@ -212,15 +212,19 @@ impl Into for Quaternion { } } -#[derive(Clone, Debug)] +#[derive(Clone, Debug, thiserror::Error)] pub enum TelemetryError { /// Unknown error + #[error("Unknown error: {0}")] Unknown(String), /// No system is connected + #[error("No system is connected: {0}")] NoSystem(String), /// Connection error + #[error("Connection error: {0}")] ConnectionError(String), /// Invalid request data + #[error("Invalid request: {0}")] InvalidRequestData(String), } @@ -257,11 +261,11 @@ impl Stream for OdometryStream { Poll::Ready(Some(rpc_result)) => match rpc_result { Ok(odometry_response) => match odometry_response.odometry { Some(rpc_odometry) => Poll::Ready(Some(Ok(Odometry::from(rpc_odometry)))), - None => Poll::Ready(Some(Err(MavErr(TelemetryError::Unknown( + None => Poll::Ready(Some(Err(RequestError::Mav(TelemetryError::Unknown( "Unexpected value".into(), ))))), }, - Err(err) => Poll::Ready(Some(Err(RpcErr(err)))), + Err(err) => Poll::Ready(Some(Err(RequestError::Rpc(err)))), }, } } diff --git a/src/lib.rs b/src/lib.rs index b8a560b..f7b036f 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -8,10 +8,15 @@ pub use generated::info; pub use generated::mocap; pub use generated::telemetry; -#[derive(Debug)] -pub enum RequestError { - MavErr(PluginMavErr), - RpcErr(tonic::Status), +#[derive(Debug, thiserror::Error)] +pub enum RequestError +where + PluginMavErr: std::error::Error, +{ + #[error("MAVLink error: {0}")] + Mav(PluginMavErr), + #[error("RPC error: {0}")] + Rpc(#[from] tonic::Status), } pub type RequestResult = Result>;