diff --git a/.clippy.toml b/.clippy.toml deleted file mode 100644 index 62ca742..0000000 --- a/.clippy.toml +++ /dev/null @@ -1 +0,0 @@ -msrv = "1.56" diff --git a/.github/workflows/CI.yml b/.github/workflows/CI.yml index a704087..be3db8d 100644 --- a/.github/workflows/CI.yml +++ b/.github/workflows/CI.yml @@ -16,7 +16,7 @@ jobs: include: - build: msrv os: ubuntu-latest - rust: 1.56 + rust: 1.65.0 - build: stable os: ubuntu-latest rust: stable @@ -36,16 +36,11 @@ jobs: - uses: actions/checkout@v2 with: submodules: true - - uses: actions-rs/toolchain@v1 + - uses: dtolnay/rust-toolchain@master with: - profile: minimal toolchain: ${{ matrix.rust }} - override: true components: rustfmt - - uses: actions-rs/cargo@v1 - with: - command: check - args: --all-targets + - run: cargo check --all-targets fmt: name: format @@ -54,16 +49,10 @@ jobs: - uses: actions/checkout@v2 with: submodules: true - - uses: actions-rs/toolchain@v1 + - uses: dtolnay/rust-toolchain@nightly with: - toolchain: nightly - override: true - profile: minimal components: rustfmt - - uses: actions-rs/cargo@v1 - with: - command: fmt - args: -- --check + - run: cargo fmt -- --check clippy: name: lint @@ -72,16 +61,13 @@ jobs: - uses: actions/checkout@v2 with: submodules: true - - uses: actions-rs/toolchain@v1 + - uses: dtolnay/rust-toolchain@nightly with: - toolchain: nightly - override: true - profile: minimal components: clippy, rustfmt - uses: actions-rs/clippy-check@v1 with: token: ${{ secrets.GITHUB_TOKEN }} - args: --tests --examples + args: --all-targets docs: name: docs @@ -90,12 +76,5 @@ jobs: - uses: actions/checkout@v2 with: submodules: true - - uses: actions-rs/toolchain@v1 - with: - toolchain: stable - override: true - profile: minimal - - uses: actions-rs/cargo@v1 - with: - command: doc - args: --no-deps + - uses: dtolnay/rust-toolchain@stable + - run: cargo doc --no-deps diff --git a/Cargo.toml b/Cargo.toml index b640b69..fc0cf9c 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -3,6 +3,7 @@ name = "libmavsdk" version = "0.1.0" authors = ["Ildar Sadykov "] edition = "2021" +rust-version = "1.65.0" [dependencies] tonic = "0.6.0" diff --git a/build.rs b/build.rs index b675d91..01be678 100644 --- a/build.rs +++ b/build.rs @@ -18,7 +18,7 @@ const PLUGINS: &[&str] = &[ fn main() -> std::io::Result<()> { for plugin in PLUGINS { - let proto_path = format!("{0}/{1}/{1}.proto", PROTO_INCLUDE_PATH, plugin); + let proto_path = format!("{PROTO_INCLUDE_PATH}/{plugin}/{plugin}.proto"); tonic_build::configure() .build_server(false) diff --git a/examples/info.rs b/examples/info.rs index 2808872..6ec7a80 100644 --- a/examples/info.rs +++ b/examples/info.rs @@ -12,13 +12,11 @@ async fn main() -> Result<(), Box> { std::process::exit(1); } - let url = args.get(0).cloned(); + let url = args.first().cloned(); - let mut system = System::connect(url).await?; + let version = System::connect(url).await?.info.get_version().await?; - let version = system.info.get_version().await?; - - println!("Version received: {:?}", version); + println!("Version received: {version:?}"); Ok(()) } diff --git a/examples/mocap.rs b/examples/mocap.rs index fafda0c..23846c4 100644 --- a/examples/mocap.rs +++ b/examples/mocap.rs @@ -13,7 +13,7 @@ async fn main() -> Result<(), Box> { std::process::exit(1); } - let url = args.get(0).cloned(); + let url = args.first().cloned(); let mut system = System::connect(url).await?; diff --git a/examples/telemetry.rs b/examples/telemetry.rs index a432fef..5a89ecb 100644 --- a/examples/telemetry.rs +++ b/examples/telemetry.rs @@ -13,11 +13,14 @@ async fn main() -> Result<(), Box> { std::process::exit(1); } - let url = args.get(0).cloned(); + let url = args.first().cloned(); - let mut system = System::connect(url).await?; + let mut stream_odometry = System::connect(url) + .await? + .telemetry + .subscribe_odometry() + .await?; - let mut stream_odometry = system.telemetry.subscribe_odometry().await?; while let Some(odometry) = stream_odometry.next().await { println!("Received: {:?}", odometry?); } diff --git a/src/info.rs b/src/info.rs index 6644b2c..8042997 100644 --- a/src/info.rs +++ b/src/info.rs @@ -4,7 +4,7 @@ mod pb { tonic::include_proto!("mavsdk.rpc.info"); } -#[derive(PartialEq, Clone, Default, Debug)] +#[derive(PartialEq, Eq, Clone, Default, Debug)] pub struct Version { /// Flight software major version pub flight_sw_major: i32, @@ -28,7 +28,7 @@ pub struct Version { impl From<&pb::Version> for Version { fn from(rpc_version: &pb::Version) -> Self { - Version { + Self { flight_sw_major: rpc_version.flight_sw_major, flight_sw_minor: rpc_version.flight_sw_minor, flight_sw_patch: rpc_version.flight_sw_patch, @@ -42,7 +42,7 @@ impl From<&pb::Version> for Version { } } -#[derive(PartialEq, Clone, Debug, thiserror::Error)] +#[derive(PartialEq, Eq, Clone, Debug, thiserror::Error)] pub enum Error { #[error("Unknown error: {0}")] Unknown(String), @@ -72,8 +72,8 @@ impl FromRpcResponse for GetVersionResult { .ok_or_else(|| Error::Unknown("Unsupported InfoResult.result value".into()))?; match info_result { - pb::info_result::Result::Success => match get_version_response.version { - Some(ref rpc_version) => Ok(Version::from(rpc_version)), + pb::info_result::Result::Success => match &get_version_response.version { + Some(rpc_version) => Ok(Version::from(rpc_version)), None => Err(Error::Unknown("Version does not received".into()).into()), }, pb::info_result::Result::Unknown => { @@ -104,8 +104,8 @@ impl Info { #[tonic::async_trait] impl crate::Connect for Info { - async fn connect(url: String) -> std::result::Result { - Ok(Info { + async fn connect(url: String) -> std::result::Result { + Ok(Self { service_client: pb::info_service_client::InfoServiceClient::connect(url).await?, }) } diff --git a/src/lib.rs b/src/lib.rs index 125ba5e..b994452 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -31,7 +31,7 @@ pub struct System { } impl System { - pub async fn connect(url: Option) -> Result { + pub async fn connect(url: Option) -> Result { let url = url.unwrap_or_else(|| String::from("http://0.0.0.0:50051")); let (mocap, info, telemetry) = try_join3( @@ -41,7 +41,7 @@ impl System { ) .await?; - Ok(System { + Ok(Self { mocap, info, telemetry, diff --git a/src/mocap.rs b/src/mocap.rs index 2658ee3..7629687 100644 --- a/src/mocap.rs +++ b/src/mocap.rs @@ -223,7 +223,7 @@ impl From for pb::Quaternion { } } -#[derive(PartialEq, Clone, Debug, thiserror::Error)] +#[derive(PartialEq, Eq, Clone, Debug, thiserror::Error)] pub enum Error { /// Unknown error #[error("Unknown error: {0}")] @@ -304,8 +304,8 @@ impl Mocap { #[tonic::async_trait] impl crate::Connect for Mocap { - async fn connect(url: String) -> std::result::Result { - Ok(Mocap { + async fn connect(url: String) -> std::result::Result { + Ok(Self { service_client: pb::mocap_service_client::MocapServiceClient::connect(url).await?, }) } diff --git a/src/telemetry.rs b/src/telemetry.rs index 3de1461..4eb77d3 100644 --- a/src/telemetry.rs +++ b/src/telemetry.rs @@ -56,7 +56,7 @@ pub struct PositionBody { impl From<&pb::PositionBody> for PositionBody { fn from(rpc_position_body: &pb::PositionBody) -> Self { - PositionBody { + Self { x_m: rpc_position_body.x_m, y_m: rpc_position_body.y_m, z_m: rpc_position_body.z_m, @@ -108,7 +108,7 @@ pub struct AngularVelocityBody { impl From<&pb::AngularVelocityBody> for AngularVelocityBody { fn from(rpc_angular_velocity_body: &pb::AngularVelocityBody) -> Self { - AngularVelocityBody { + Self { roll_rad_s: rpc_angular_velocity_body.roll_rad_s, pitch_rad_s: rpc_angular_velocity_body.pitch_rad_s, yaw_rad_s: rpc_angular_velocity_body.yaw_rad_s, @@ -136,8 +136,8 @@ pub struct Covariance { } impl From for Odometry { - fn from(rpc_odometry: pb::Odometry) -> Odometry { - Odometry { + fn from(rpc_odometry: pb::Odometry) -> Self { + Self { time_usec: 0, frame_id: MavFrame::from_i32(rpc_odometry.frame_id).unwrap(), child_frame_id: MavFrame::from_i32(rpc_odometry.child_frame_id).unwrap(), @@ -266,10 +266,10 @@ pub type OdometryResult = RequestResult; #[tonic::async_trait] impl crate::Connect for Telemetry { - async fn connect(url: String) -> std::result::Result { + async fn connect(url: String) -> std::result::Result { let service_client = pb::telemetry_service_client::TelemetryServiceClient::connect(url).await?; - Ok(Telemetry { service_client }) + Ok(Self { service_client }) } }