From 38e85b6ababe95ba209df33aa3f5977a18e3e371 Mon Sep 17 00:00:00 2001
From: pv42 <pv42.97@gmail.com>
Date: Sun, 8 Sep 2024 14:18:24 +0200
Subject: [PATCH] doc: replace block with yield, move file comment, fmt cargo

---
 mavlink-core/Cargo.toml                   | 4 ++--
 mavlink-core/src/async_connection/file.rs | 4 ++--
 mavlink-core/src/async_connection/mod.rs  | 2 +-
 mavlink-core/src/async_connection/tcp.rs  | 6 +++---
 mavlink-core/src/async_connection/udp.rs  | 2 ++
 mavlink-core/src/lib.rs                   | 1 -
 6 files changed, 10 insertions(+), 9 deletions(-)

diff --git a/mavlink-core/Cargo.toml b/mavlink-core/Cargo.toml
index eb749b0..5bf97b9 100644
--- a/mavlink-core/Cargo.toml
+++ b/mavlink-core/Cargo.toml
@@ -26,7 +26,7 @@ embedded-io-async = { version = "0.6.1", optional = true }
 serde = { version = "1.0.115", optional = true, features = ["derive"] }
 serde_arrays = { version = "0.1.0", optional = true }
 serial = { version = "0.4", optional = true }
-tokio = { version = "1.0", default-features = false, features = ["io-util", "net", "sync", "fs", ], optional = true }
+tokio = { version = "1.0", default-features = false, features = ["io-util", "net", "sync", "fs"], optional = true }
 sha2 = { version = "0.10", optional = true }
 async-trait = { version = "0.1.18", optional = true }
 
@@ -46,4 +46,4 @@ async-trait = { version = "0.1.18", optional = true }
 default = ["std", "tcp", "udp", "direct-serial", "serde"]
 
 [dev-dependencies]
-tokio = { version = "1.0", default-features = false, features = ["io-util", "net", "sync", "fs","macros", "rt" ] }
\ No newline at end of file
+tokio = { version = "1.0", default-features = false, features = ["io-util", "net", "sync", "fs", "macros", "rt"] }
\ No newline at end of file
diff --git a/mavlink-core/src/async_connection/file.rs b/mavlink-core/src/async_connection/file.rs
index 8522736..5dae56d 100644
--- a/mavlink-core/src/async_connection/file.rs
+++ b/mavlink-core/src/async_connection/file.rs
@@ -1,3 +1,5 @@
+//! Async File MAVLINK connection
+
 use core::ops::DerefMut;
 
 use super::AsyncMavConnection;
@@ -15,8 +17,6 @@ use crate::read_versioned_msg_async;
 #[cfg(feature = "signing")]
 use crate::{read_versioned_msg_async_signed, SigningConfig, SigningData};
 
-/// File MAVLINK connection
-
 pub async fn open(file_path: &str) -> io::Result<AsyncFileConnection> {
     let file = File::open(file_path).await?;
     Ok(AsyncFileConnection {
diff --git a/mavlink-core/src/async_connection/mod.rs b/mavlink-core/src/async_connection/mod.rs
index a708a67..35e2fa0 100644
--- a/mavlink-core/src/async_connection/mod.rs
+++ b/mavlink-core/src/async_connection/mod.rs
@@ -18,7 +18,7 @@ use crate::SigningConfig;
 pub trait AsyncMavConnection<M: Message + Sync + Send> {
     /// Receive a mavlink message.
     ///
-    /// Wait until a valid frame is received, ignoring invalid messages.
+    /// Yield until a valid frame is received, ignoring invalid messages.
     async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
 
     /// Send a mavlink message
diff --git a/mavlink-core/src/async_connection/tcp.rs b/mavlink-core/src/async_connection/tcp.rs
index e8171c7..b0307d3 100644
--- a/mavlink-core/src/async_connection/tcp.rs
+++ b/mavlink-core/src/async_connection/tcp.rs
@@ -1,3 +1,5 @@
+//! Async TCP MAVLink connection
+
 use super::{get_socket_addr, AsyncMavConnection};
 use crate::async_peek_reader::AsyncPeekReader;
 use crate::{MavHeader, MavlinkVersion, Message};
@@ -15,8 +17,6 @@ use crate::{
     read_versioned_msg_async_signed, write_versioned_msg_async_signed, SigningConfig, SigningData,
 };
 
-/// TCP MAVLink connection
-
 pub async fn select_protocol<M: Message + Sync + Send>(
     address: &str,
 ) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
@@ -57,7 +57,7 @@ pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConn
     let addr = get_socket_addr(address)?;
     let listener = TcpListener::bind(addr).await?;
 
-    //For now we only accept one incoming stream: this blocks until we get one
+    //For now we only accept one incoming stream: this yields until we get one
     match listener.accept().await {
         Ok((socket, _)) => {
             let (reader, writer) = socket.into_split();
diff --git a/mavlink-core/src/async_connection/udp.rs b/mavlink-core/src/async_connection/udp.rs
index cd945e8..c3082d0 100644
--- a/mavlink-core/src/async_connection/udp.rs
+++ b/mavlink-core/src/async_connection/udp.rs
@@ -1,3 +1,5 @@
+//! Async UDP MAVLink connection
+
 use core::{ops::DerefMut, task::Poll};
 use std::{collections::VecDeque, io::Read, sync::Arc};
 
diff --git a/mavlink-core/src/lib.rs b/mavlink-core/src/lib.rs
index 7a33419..8af70ad 100644
--- a/mavlink-core/src/lib.rs
+++ b/mavlink-core/src/lib.rs
@@ -958,7 +958,6 @@ fn read_v2_raw_message_inner<M: Message, R: Read>(
 }
 
 /// Async read a raw buffer with the mavlink message
-///
 /// V2 maximum size is 280 bytes: `<https://mavlink.io/en/guide/serialization.html>`
 #[cfg(feature = "tokio-1")]
 pub async fn read_v2_raw_message_async<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
-- 
GitLab