Skip to content

Commit a44abd2

Browse files
pv42patrickelectric
authored andcommitted
feat: add ConnectionAddress type and Connectable traits
1 parent a973af3 commit a44abd2

File tree

13 files changed

+394
-283
lines changed

13 files changed

+394
-283
lines changed

mavlink-core/src/async_connection/direct_serial.rs

Lines changed: 29 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,15 @@
33
use core::ops::DerefMut;
44
use std::io;
55

6+
use async_trait::async_trait;
67
use tokio::sync::Mutex;
78
use tokio_serial::{SerialPort, SerialPortBuilderExt, SerialStream};
89

9-
use crate::{async_peek_reader::AsyncPeekReader, MavHeader, MavlinkVersion, Message};
10+
use super::AsyncConnectable;
11+
use crate::{
12+
async_peek_reader::AsyncPeekReader, connectable::SerialConnectable, MavHeader, MavlinkVersion,
13+
Message,
14+
};
1015

1116
#[cfg(not(feature = "signing"))]
1217
use crate::{read_versioned_msg_async, write_versioned_msg_async};
@@ -17,38 +22,6 @@ use crate::{
1722

1823
use super::AsyncMavConnection;
1924

20-
pub fn open(settings: &str) -> io::Result<AsyncSerialConnection> {
21-
let settings_toks: Vec<&str> = settings.split(':').collect();
22-
if settings_toks.len() < 2 {
23-
return Err(io::Error::new(
24-
io::ErrorKind::AddrNotAvailable,
25-
"Incomplete port settings",
26-
));
27-
}
28-
29-
let Ok(baud) = settings_toks[1].parse::<u32>() else {
30-
return Err(io::Error::new(
31-
io::ErrorKind::AddrNotAvailable,
32-
"Invalid baud rate",
33-
));
34-
};
35-
36-
let port_name = settings_toks[0];
37-
let mut port = tokio_serial::new(port_name, baud).open_native_async()?;
38-
port.set_data_bits(tokio_serial::DataBits::Eight)?;
39-
port.set_parity(tokio_serial::Parity::None)?;
40-
port.set_stop_bits(tokio_serial::StopBits::One)?;
41-
port.set_flow_control(tokio_serial::FlowControl::None)?;
42-
43-
Ok(AsyncSerialConnection {
44-
port: Mutex::new(AsyncPeekReader::new(port)),
45-
sequence: Mutex::new(0),
46-
protocol_version: MavlinkVersion::V2,
47-
#[cfg(feature = "signing")]
48-
signing_data: None,
49-
})
50-
}
51-
5225
pub struct AsyncSerialConnection {
5326
port: Mutex<AsyncPeekReader<SerialStream>>,
5427
sequence: Mutex<u8>,
@@ -118,3 +91,26 @@ impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncSerialConnection {
11891
self.signing_data = signing_data.map(SigningData::from_config)
11992
}
12093
}
94+
95+
#[async_trait]
96+
impl AsyncConnectable for SerialConnectable {
97+
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
98+
where
99+
M: Message + Sync + Send,
100+
{
101+
let mut port =
102+
tokio_serial::new(&self.port_name, self.baud_rate as u32).open_native_async()?;
103+
port.set_data_bits(tokio_serial::DataBits::Eight)?;
104+
port.set_parity(tokio_serial::Parity::None)?;
105+
port.set_stop_bits(tokio_serial::StopBits::One)?;
106+
port.set_flow_control(tokio_serial::FlowControl::None)?;
107+
108+
Ok(Box::new(AsyncSerialConnection {
109+
port: Mutex::new(AsyncPeekReader::new(port)),
110+
sequence: Mutex::new(0),
111+
protocol_version: MavlinkVersion::V2,
112+
#[cfg(feature = "signing")]
113+
signing_data: None,
114+
}))
115+
}
116+
}

mavlink-core/src/async_connection/file.rs

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,11 +2,13 @@
22
33
use core::ops::DerefMut;
44

5-
use super::AsyncMavConnection;
5+
use super::{AsyncConnectable, AsyncMavConnection};
6+
use crate::connectable::FileConnectable;
67
use crate::error::{MessageReadError, MessageWriteError};
78

89
use crate::{async_peek_reader::AsyncPeekReader, MavHeader, MavlinkVersion, Message};
910

11+
use async_trait::async_trait;
1012
use tokio::fs::File;
1113
use tokio::io;
1214
use tokio::sync::Mutex;
@@ -81,3 +83,13 @@ impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncFileConnection {
8183
self.signing_data = signing_data.map(SigningData::from_config)
8284
}
8385
}
86+
87+
#[async_trait]
88+
impl AsyncConnectable for FileConnectable {
89+
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
90+
where
91+
M: Message + Sync + Send,
92+
{
93+
Ok(Box::new(open(&self.address).await?))
94+
}
95+
}

mavlink-core/src/async_connection/mod.rs

Lines changed: 27 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
1+
use async_trait::async_trait;
12
use tokio::io;
23

3-
use crate::{MavFrame, MavHeader, MavlinkVersion, Message};
4+
use crate::{connectable::ConnectionAddress, MavFrame, MavHeader, MavlinkVersion, Message};
45

56
#[cfg(feature = "tcp")]
67
mod tcp;
@@ -81,43 +82,9 @@ pub trait AsyncMavConnection<M: Message + Sync + Send> {
8182
pub async fn connect_async<M: Message + Sync + Send>(
8283
address: &str,
8384
) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
84-
let protocol_err = Err(io::Error::new(
85-
io::ErrorKind::AddrNotAvailable,
86-
"Protocol unsupported",
87-
));
88-
89-
if cfg!(feature = "tcp") && address.starts_with("tcp") {
90-
#[cfg(feature = "tcp")]
91-
{
92-
tcp::select_protocol(address).await
93-
}
94-
#[cfg(not(feature = "tcp"))]
95-
{
96-
protocol_err
97-
}
98-
} else if cfg!(feature = "udp") && address.starts_with("udp") {
99-
#[cfg(feature = "udp")]
100-
{
101-
udp::select_protocol(address).await
102-
}
103-
#[cfg(not(feature = "udp"))]
104-
{
105-
protocol_err
106-
}
107-
} else if cfg!(feature = "direct-serial") && address.starts_with("serial") {
108-
#[cfg(feature = "direct-serial")]
109-
{
110-
Ok(Box::new(direct_serial::open(&address["serial:".len()..])?))
111-
}
112-
#[cfg(not(feature = "direct-serial"))]
113-
{
114-
protocol_err
115-
}
116-
} else if address.starts_with("file") {
117-
Ok(Box::new(file::open(&address["file:".len()..]).await?))
118-
} else {
119-
protocol_err
120-
}
85+
ConnectionAddress::parse_address(address)?
86+
.connect_async::<M>()
87+
.await
12188
}
12289

12390
/// Returns the socket address for the given address.
@@ -135,3 +102,25 @@ pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
135102
};
136103
Ok(addr)
137104
}
105+
106+
#[async_trait]
107+
pub trait AsyncConnectable {
108+
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
109+
where
110+
M: Message + Sync + Send;
111+
}
112+
113+
#[async_trait]
114+
impl AsyncConnectable for ConnectionAddress {
115+
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
116+
where
117+
M: Message + Sync + Send,
118+
{
119+
match self {
120+
Self::Tcp(connectable) => connectable.connect_async::<M>().await,
121+
Self::Udp(connectable) => connectable.connect_async::<M>().await,
122+
Self::Serial(connectable) => connectable.connect_async::<M>().await,
123+
Self::File(connectable) => connectable.connect_async::<M>().await,
124+
}
125+
}
126+
}

mavlink-core/src/async_connection/tcp.rs

Lines changed: 18 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,11 @@
11
//! Async TCP MAVLink connection
22
3-
use super::{get_socket_addr, AsyncMavConnection};
3+
use super::{get_socket_addr, AsyncConnectable, AsyncMavConnection};
44
use crate::async_peek_reader::AsyncPeekReader;
5+
use crate::connectable::TcpConnectable;
56
use crate::{MavHeader, MavlinkVersion, Message};
67

8+
use async_trait::async_trait;
79
use core::ops::DerefMut;
810
use tokio::io;
911
use tokio::net::tcp::{OwnedReadHalf, OwnedWriteHalf};
@@ -17,23 +19,6 @@ use crate::{
1719
read_versioned_msg_async_signed, write_versioned_msg_async_signed, SigningConfig, SigningData,
1820
};
1921

20-
pub async fn select_protocol<M: Message + Sync + Send>(
21-
address: &str,
22-
) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
23-
let connection = if let Some(address) = address.strip_prefix("tcpout:") {
24-
tcpout(address).await
25-
} else if let Some(address) = address.strip_prefix("tcpin:") {
26-
tcpin(address).await
27-
} else {
28-
Err(io::Error::new(
29-
io::ErrorKind::AddrNotAvailable,
30-
"Protocol unsupported",
31-
))
32-
};
33-
34-
Ok(Box::new(connection?))
35-
}
36-
3722
pub async fn tcpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncTcpConnection> {
3823
let addr = get_socket_addr(address)?;
3924

@@ -154,3 +139,18 @@ impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncTcpConnection {
154139
self.signing_data = signing_data.map(SigningData::from_config)
155140
}
156141
}
142+
143+
#[async_trait]
144+
impl AsyncConnectable for TcpConnectable {
145+
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
146+
where
147+
M: Message + Sync + Send,
148+
{
149+
let conn = if self.is_out {
150+
tcpout(&self.address).await
151+
} else {
152+
tcpin(&self.address).await
153+
};
154+
Ok(Box::new(conn?))
155+
}
156+
}

mavlink-core/src/async_connection/udp.rs

Lines changed: 25 additions & 46 deletions
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,20 @@
33
use core::{ops::DerefMut, task::Poll};
44
use std::{collections::VecDeque, io::Read, sync::Arc};
55

6+
use async_trait::async_trait;
67
use tokio::{
78
io::{self, AsyncRead, ReadBuf},
89
net::UdpSocket,
910
sync::Mutex,
1011
};
1112

12-
use crate::{async_peek_reader::AsyncPeekReader, MavHeader, MavlinkVersion, Message};
13+
use crate::{
14+
async_peek_reader::AsyncPeekReader,
15+
connectable::{UdpConnectable, UdpMode},
16+
MavHeader, MavlinkVersion, Message,
17+
};
1318

14-
use super::{get_socket_addr, AsyncMavConnection};
19+
use super::{get_socket_addr, AsyncConnectable, AsyncMavConnection};
1520

1621
#[cfg(not(feature = "signing"))]
1722
use crate::{read_versioned_msg_async, write_versioned_msg_async};
@@ -20,50 +25,6 @@ use crate::{
2025
read_versioned_msg_async_signed, write_versioned_msg_signed, SigningConfig, SigningData,
2126
};
2227

23-
pub async fn select_protocol<M: Message + Sync + Send>(
24-
address: &str,
25-
) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
26-
let connection = if let Some(address) = address.strip_prefix("udpin:") {
27-
udpin(address).await
28-
} else if let Some(address) = address.strip_prefix("udpout:") {
29-
udpout(address).await
30-
} else if let Some(address) = address.strip_prefix("udpbcast:") {
31-
udpbcast(address).await
32-
} else {
33-
Err(io::Error::new(
34-
io::ErrorKind::AddrNotAvailable,
35-
"Protocol unsupported",
36-
))
37-
};
38-
39-
Ok(Box::new(connection?))
40-
}
41-
42-
pub async fn udpbcast<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> {
43-
let addr = get_socket_addr(address)?;
44-
let socket = UdpSocket::bind("0.0.0.0:0").await?;
45-
socket
46-
.set_broadcast(true)
47-
.expect("Couldn't bind to broadcast address.");
48-
AsyncUdpConnection::new(socket, false, Some(addr))
49-
}
50-
51-
pub async fn udpout<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> {
52-
let addr = get_socket_addr(address)?;
53-
let socket = UdpSocket::bind("0.0.0.0:0").await?;
54-
AsyncUdpConnection::new(socket, false, Some(addr))
55-
}
56-
57-
pub async fn udpin<T: std::net::ToSocketAddrs>(address: T) -> io::Result<AsyncUdpConnection> {
58-
let addr = address
59-
.to_socket_addrs()
60-
.unwrap()
61-
.next()
62-
.expect("Invalid address");
63-
let socket = UdpSocket::bind(addr).await?;
64-
AsyncUdpConnection::new(socket, true, None)
65-
}
66-
6728
struct UdpRead {
6829
socket: Arc<UdpSocket>,
6930
buffer: VecDeque<u8>,
@@ -235,6 +196,24 @@ impl<M: Message + Sync + Send> AsyncMavConnection<M> for AsyncUdpConnection {
235196
}
236197
}
237198

199+
#[async_trait]
200+
impl AsyncConnectable for UdpConnectable {
201+
async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
202+
where
203+
M: Message + Sync + Send,
204+
{
205+
let (addr, server, dest): (&str, _, _) = match self.mode {
206+
UdpMode::Udpin => (&self.address, true, None),
207+
_ => ("0.0.0.0:0", false, Some(get_socket_addr(&self.address)?)),
208+
};
209+
let socket = UdpSocket::bind(addr).await?;
210+
if matches!(self.mode, UdpMode::Udpcast) {
211+
socket.set_broadcast(true)?;
212+
}
213+
Ok(Box::new(AsyncUdpConnection::new(socket, server, dest)?))
214+
}
215+
}
216+
238217
#[cfg(test)]
239218
mod tests {
240219
use super::*;

0 commit comments

Comments
 (0)