diff --git a/mavlink-core/src/async_connection/tcp.rs b/mavlink-core/src/async_connection/tcp.rs index b0307d377d..4cd1f9ac9a 100644 --- a/mavlink-core/src/async_connection/tcp.rs +++ b/mavlink-core/src/async_connection/tcp.rs @@ -34,14 +34,14 @@ pub async fn select_protocol( Ok(Box::new(connection?)) } -pub async fn tcpout(address: T) -> io::Result { +pub async fn tcpout(address: T) -> io::Result { let addr = get_socket_addr(address)?; let socket = TcpStream::connect(addr).await?; let (reader, writer) = socket.into_split(); - Ok(TcpConnection { + Ok(AsyncTcpConnection { reader: Mutex::new(AsyncPeekReader::new(reader)), writer: Mutex::new(TcpWrite { socket: writer, @@ -53,7 +53,7 @@ pub async fn tcpout(address: T) -> io::Result(address: T) -> io::Result { +pub async fn tcpin(address: T) -> io::Result { let addr = get_socket_addr(address)?; let listener = TcpListener::bind(addr).await?; @@ -61,7 +61,7 @@ pub async fn tcpin(address: T) -> io::Result { let (reader, writer) = socket.into_split(); - return Ok(TcpConnection { + return Ok(AsyncTcpConnection { reader: Mutex::new(AsyncPeekReader::new(reader)), writer: Mutex::new(TcpWrite { socket: writer, @@ -83,7 +83,7 @@ pub async fn tcpin(address: T) -> io::Result>, writer: Mutex, protocol_version: MavlinkVersion, @@ -97,7 +97,7 @@ struct TcpWrite { } #[async_trait::async_trait] -impl AsyncMavConnection for TcpConnection { +impl AsyncMavConnection for AsyncTcpConnection { async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> { let mut reader = self.reader.lock().await; #[cfg(not(feature = "signing"))] diff --git a/mavlink-core/src/async_connection/udp.rs b/mavlink-core/src/async_connection/udp.rs index c3082d0edb..3f06b83e1d 100644 --- a/mavlink-core/src/async_connection/udp.rs +++ b/mavlink-core/src/async_connection/udp.rs @@ -22,7 +22,7 @@ use crate::{ pub async fn select_protocol( address: &str, -) -> tokio::io::Result + Sync + Send>> { +) -> io::Result + Sync + Send>> { let connection = if let Some(address) = address.strip_prefix("udpin:") { udpin(address).await } else if let Some(address) = address.strip_prefix("udpout:") { @@ -30,8 +30,8 @@ pub async fn select_protocol( } else if let Some(address) = address.strip_prefix("udpbcast:") { udpbcast(address).await } else { - Err(tokio::io::Error::new( - tokio::io::ErrorKind::AddrNotAvailable, + Err(io::Error::new( + io::ErrorKind::AddrNotAvailable, "Protocol unsupported", )) }; @@ -39,29 +39,29 @@ pub async fn select_protocol( Ok(Box::new(connection?)) } -pub async fn udpbcast(address: T) -> tokio::io::Result { +pub async fn udpbcast(address: T) -> io::Result { let addr = get_socket_addr(address)?; let socket = UdpSocket::bind("0.0.0.0:0").await?; socket .set_broadcast(true) .expect("Couldn't bind to broadcast address."); - UdpConnection::new(socket, false, Some(addr)) + AsyncUdpConnection::new(socket, false, Some(addr)) } -pub async fn udpout(address: T) -> tokio::io::Result { +pub async fn udpout(address: T) -> io::Result { let addr = get_socket_addr(address)?; let socket = UdpSocket::bind("0.0.0.0:0").await?; - UdpConnection::new(socket, false, Some(addr)) + AsyncUdpConnection::new(socket, false, Some(addr)) } -pub async fn udpin(address: T) -> tokio::io::Result { +pub async fn udpin(address: T) -> io::Result { let addr = address .to_socket_addrs() .unwrap() .next() .expect("Invalid address"); let socket = UdpSocket::bind(addr).await?; - UdpConnection::new(socket, true, None) + AsyncUdpConnection::new(socket, true, None) } struct UdpRead { @@ -75,7 +75,7 @@ impl AsyncRead for UdpRead { fn poll_read( mut self: core::pin::Pin<&mut Self>, cx: &mut core::task::Context<'_>, - buf: &mut tokio::io::ReadBuf<'_>, + buf: &mut io::ReadBuf<'_>, ) -> Poll> { if self.buffer.is_empty() { let mut read_buffer = [0u8; MTU_SIZE]; @@ -115,7 +115,7 @@ struct UdpWrite { sequence: u8, } -pub struct UdpConnection { +pub struct AsyncUdpConnection { reader: Mutex>, writer: Mutex, protocol_version: MavlinkVersion, @@ -124,12 +124,12 @@ pub struct UdpConnection { signing_data: Option, } -impl UdpConnection { +impl AsyncUdpConnection { fn new( socket: UdpSocket, server: bool, dest: Option, - ) -> tokio::io::Result { + ) -> io::Result { let socket = Arc::new(socket); Ok(Self { server, @@ -151,7 +151,7 @@ impl UdpConnection { } #[async_trait::async_trait] -impl AsyncMavConnection for UdpConnection { +impl AsyncMavConnection for AsyncUdpConnection { async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> { let mut reader = self.reader.lock().await; @@ -238,7 +238,7 @@ impl AsyncMavConnection for UdpConnection { #[cfg(test)] mod tests { use super::*; - use tokio::io::AsyncReadExt; + use io::AsyncReadExt; #[tokio::test] async fn test_datagram_buffering() {