diff --git a/mavlink-core/src/async_connection/tcp.rs b/mavlink-core/src/async_connection/tcp.rs index b0307d377d18bbf3a43bf2ad69b190c9246b8958..4cd1f9ac9a1754a7d86b392dc3cd98ced08e4ca8 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<M: Message + Sync + Send>( Ok(Box::new(connection?)) } -pub async fn tcpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConnection> { +pub async fn tcpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncTcpConnection> { 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<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpCon }) } -pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConnection> { +pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncTcpConnection> { let addr = get_socket_addr(address)?; let listener = TcpListener::bind(addr).await?; @@ -61,7 +61,7 @@ pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConn match listener.accept().await { Ok((socket, _)) => { 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<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConn )) } -pub struct TcpConnection { +pub struct AsyncTcpConnection { reader: Mutex<AsyncPeekReader<OwnedReadHalf>>, writer: Mutex<TcpWrite>, protocol_version: MavlinkVersion, @@ -97,7 +97,7 @@ struct TcpWrite { } #[async_trait::async_trait] -impl<M: Message + Sync + Send> AsyncMavConnection<M> for TcpConnection { +impl<M: Message + Sync + Send> AsyncMavConnection<M> 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 c3082d0edbc7d6a19d25cacf43e71777a1489395..3f06b83e1d58e65e6bff246adbba05b388b41c4e 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<M: Message + Sync + Send>( address: &str, -) -> tokio::io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> { +) -> io::Result<Box<dyn AsyncMavConnection<M> + 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<M: Message + Sync + Send>( } 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<M: Message + Sync + Send>( Ok(Box::new(connection?)) } -pub async fn udpbcast<T: std::net::ToSocketAddrs>(address: T) -> tokio::io::Result<UdpConnection> { +pub async fn udpbcast<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> { 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<T: std::net::ToSocketAddrs>(address: T) -> tokio::io::Result<UdpConnection> { +pub async fn udpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> { 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<T: std::net::ToSocketAddrs>(address: T) -> tokio::io::Result<UdpConnection> { +pub async fn udpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> { 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<io::Result<()>> { 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<AsyncPeekReader<UdpRead>>, writer: Mutex<UdpWrite>, protocol_version: MavlinkVersion, @@ -124,12 +124,12 @@ pub struct UdpConnection { signing_data: Option<SigningData>, } -impl UdpConnection { +impl AsyncUdpConnection { fn new( socket: UdpSocket, server: bool, dest: Option<std::net::SocketAddr>, - ) -> tokio::io::Result<Self> { + ) -> io::Result<Self> { let socket = Arc::new(socket); Ok(Self { server, @@ -151,7 +151,7 @@ impl UdpConnection { } #[async_trait::async_trait] -impl<M: Message + Sync + Send> AsyncMavConnection<M> for UdpConnection { +impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncUdpConnection { async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> { let mut reader = self.reader.lock().await; @@ -238,7 +238,7 @@ impl<M: Message + Sync + Send> AsyncMavConnection<M> for UdpConnection { #[cfg(test)] mod tests { use super::*; - use tokio::io::AsyncReadExt; + use io::AsyncReadExt; #[tokio::test] async fn test_datagram_buffering() {