Skip to content

Commit 18305e3

Browse files
committed
fix: rename tcp/udp connection to AsyncTcpConnection/AsyncUdpConnection, remove unneeded tokio:: prefixes
1 parent 4377d2e commit 18305e3

File tree

2 files changed

+21
-21
lines changed

2 files changed

+21
-21
lines changed

mavlink-core/src/async_connection/tcp.rs

+6-6
Original file line numberDiff line numberDiff line change
@@ -34,14 +34,14 @@ pub async fn select_protocol<M: Message + Sync + Send>(
3434
Ok(Box::new(connection?))
3535
}
3636

37-
pub async fn tcpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
37+
pub async fn tcpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncTcpConnection> {
3838
let addr = get_socket_addr(address)?;
3939

4040
let socket = TcpStream::connect(addr).await?;
4141

4242
let (reader, writer) = socket.into_split();
4343

44-
Ok(TcpConnection {
44+
Ok(AsyncTcpConnection {
4545
reader: Mutex::new(AsyncPeekReader::new(reader)),
4646
writer: Mutex::new(TcpWrite {
4747
socket: writer,
@@ -53,15 +53,15 @@ pub async fn tcpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpCon
5353
})
5454
}
5555

56-
pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
56+
pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncTcpConnection> {
5757
let addr = get_socket_addr(address)?;
5858
let listener = TcpListener::bind(addr).await?;
5959

6060
//For now we only accept one incoming stream: this yields until we get one
6161
match listener.accept().await {
6262
Ok((socket, _)) => {
6363
let (reader, writer) = socket.into_split();
64-
return Ok(TcpConnection {
64+
return Ok(AsyncTcpConnection {
6565
reader: Mutex::new(AsyncPeekReader::new(reader)),
6666
writer: Mutex::new(TcpWrite {
6767
socket: writer,
@@ -83,7 +83,7 @@ pub async fn tcpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<TcpConn
8383
))
8484
}
8585

86-
pub struct TcpConnection {
86+
pub struct AsyncTcpConnection {
8787
reader: Mutex<AsyncPeekReader<OwnedReadHalf>>,
8888
writer: Mutex<TcpWrite>,
8989
protocol_version: MavlinkVersion,
@@ -97,7 +97,7 @@ struct TcpWrite {
9797
}
9898

9999
#[async_trait::async_trait]
100-
impl<M: Message + Sync + Send> AsyncMavConnection<M> for TcpConnection {
100+
impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncTcpConnection {
101101
async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> {
102102
let mut reader = self.reader.lock().await;
103103
#[cfg(not(feature = "signing"))]

mavlink-core/src/async_connection/udp.rs

+15-15
Original file line numberDiff line numberDiff line change
@@ -22,46 +22,46 @@ use crate::{
2222

2323
pub async fn select_protocol<M: Message + Sync + Send>(
2424
address: &str,
25-
) -> tokio::io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
25+
) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
2626
let connection = if let Some(address) = address.strip_prefix("udpin:") {
2727
udpin(address).await
2828
} else if let Some(address) = address.strip_prefix("udpout:") {
2929
udpout(address).await
3030
} else if let Some(address) = address.strip_prefix("udpbcast:") {
3131
udpbcast(address).await
3232
} else {
33-
Err(tokio::io::Error::new(
34-
tokio::io::ErrorKind::AddrNotAvailable,
33+
Err(io::Error::new(
34+
io::ErrorKind::AddrNotAvailable,
3535
"Protocol unsupported",
3636
))
3737
};
3838

3939
Ok(Box::new(connection?))
4040
}
4141

42-
pub async fn udpbcast<T: std::net::ToSocketAddrs>(address: T) -> tokio::io::Result<UdpConnection> {
42+
pub async fn udpbcast<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> {
4343
let addr = get_socket_addr(address)?;
4444
let socket = UdpSocket::bind("0.0.0.0:0").await?;
4545
socket
4646
.set_broadcast(true)
4747
.expect("Couldn't bind to broadcast address.");
48-
UdpConnection::new(socket, false, Some(addr))
48+
AsyncUdpConnection::new(socket, false, Some(addr))
4949
}
5050

51-
pub async fn udpout<T: std::net::ToSocketAddrs>(address: T) -> tokio::io::Result<UdpConnection> {
51+
pub async fn udpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> {
5252
let addr = get_socket_addr(address)?;
5353
let socket = UdpSocket::bind("0.0.0.0:0").await?;
54-
UdpConnection::new(socket, false, Some(addr))
54+
AsyncUdpConnection::new(socket, false, Some(addr))
5555
}
5656

57-
pub async fn udpin<T: std::net::ToSocketAddrs>(address: T) -> tokio::io::Result<UdpConnection> {
57+
pub async fn udpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> {
5858
let addr = address
5959
.to_socket_addrs()
6060
.unwrap()
6161
.next()
6262
.expect("Invalid address");
6363
let socket = UdpSocket::bind(addr).await?;
64-
UdpConnection::new(socket, true, None)
64+
AsyncUdpConnection::new(socket, true, None)
6565
}
6666

6767
struct UdpRead {
@@ -75,7 +75,7 @@ impl AsyncRead for UdpRead {
7575
fn poll_read(
7676
mut self: core::pin::Pin<&mut Self>,
7777
cx: &mut core::task::Context<'_>,
78-
buf: &mut tokio::io::ReadBuf<'_>,
78+
buf: &mut io::ReadBuf<'_>,
7979
) -> Poll<io::Result<()>> {
8080
if self.buffer.is_empty() {
8181
let mut read_buffer = [0u8; MTU_SIZE];
@@ -115,7 +115,7 @@ struct UdpWrite {
115115
sequence: u8,
116116
}
117117

118-
pub struct UdpConnection {
118+
pub struct AsyncUdpConnection {
119119
reader: Mutex<AsyncPeekReader<UdpRead>>,
120120
writer: Mutex<UdpWrite>,
121121
protocol_version: MavlinkVersion,
@@ -124,12 +124,12 @@ pub struct UdpConnection {
124124
signing_data: Option<SigningData>,
125125
}
126126

127-
impl UdpConnection {
127+
impl AsyncUdpConnection {
128128
fn new(
129129
socket: UdpSocket,
130130
server: bool,
131131
dest: Option<std::net::SocketAddr>,
132-
) -> tokio::io::Result<Self> {
132+
) -> io::Result<Self> {
133133
let socket = Arc::new(socket);
134134
Ok(Self {
135135
server,
@@ -151,7 +151,7 @@ impl UdpConnection {
151151
}
152152

153153
#[async_trait::async_trait]
154-
impl<M: Message + Sync + Send> AsyncMavConnection<M> for UdpConnection {
154+
impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncUdpConnection {
155155
async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> {
156156
let mut reader = self.reader.lock().await;
157157

@@ -238,7 +238,7 @@ impl<M: Message + Sync + Send> AsyncMavConnection<M> for UdpConnection {
238238
#[cfg(test)]
239239
mod tests {
240240
use super::*;
241-
use tokio::io::AsyncReadExt;
241+
use io::AsyncReadExt;
242242

243243
#[tokio::test]
244244
async fn test_datagram_buffering() {

0 commit comments

Comments
 (0)