mavlink_core/async_connection/
mod.rs1use async_trait::async_trait;
2use tokio::io;
3
4use crate::{connectable::ConnectionAddress, MavFrame, MavHeader, MavlinkVersion, Message};
5
6#[cfg(feature = "tcp")]
7mod tcp;
8
9#[cfg(feature = "udp")]
10mod udp;
11
12#[cfg(feature = "direct-serial")]
13mod direct_serial;
14
15mod file;
16
17#[cfg(feature = "signing")]
18use crate::SigningConfig;
19
20#[async_trait::async_trait]
22pub trait AsyncMavConnection<M: Message + Sync + Send> {
23 async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
27
28 async fn send(
30 &self,
31 header: &MavHeader,
32 data: &M,
33 ) -> Result<usize, crate::error::MessageWriteError>;
34
35 fn set_protocol_version(&mut self, version: MavlinkVersion);
37 fn protocol_version(&self) -> MavlinkVersion;
39
40 fn set_allow_recv_any_version(&mut self, allow: bool);
44 fn allow_recv_any_version(&self) -> bool;
46
47 async fn send_frame(
49 &self,
50 frame: &MavFrame<M>,
51 ) -> Result<usize, crate::error::MessageWriteError> {
52 self.send(&frame.header, &frame.msg).await
53 }
54
55 async fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
57 let (header, msg) = self.recv().await?;
58 let protocol_version = self.protocol_version();
59 Ok(MavFrame {
60 header,
61 msg,
62 protocol_version,
63 })
64 }
65
66 async fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
68 let header = MavHeader::default();
69 self.send(&header, data).await
70 }
71
72 #[cfg(feature = "signing")]
74 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
75}
76
77pub async fn connect_async<M: Message + Sync + Send>(
92 address: &str,
93) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
94 ConnectionAddress::parse_address(address)?
95 .connect_async::<M>()
96 .await
97}
98
99#[cfg(any(feature = "tcp", feature = "udp"))]
101pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
102 address: T,
103) -> Result<std::net::SocketAddr, io::Error> {
104 let addr = match address.to_socket_addrs()?.next() {
105 Some(addr) => addr,
106 None => {
107 return Err(io::Error::new(
108 io::ErrorKind::Other,
109 "Host address lookup failed",
110 ));
111 }
112 };
113 Ok(addr)
114}
115
116#[async_trait]
120pub trait AsyncConnectable {
121 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
123 where
124 M: Message + Sync + Send;
125}
126
127#[async_trait]
128impl AsyncConnectable for ConnectionAddress {
129 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
130 where
131 M: Message + Sync + Send,
132 {
133 match self {
134 #[cfg(feature = "tcp")]
135 Self::Tcp(connectable) => connectable.connect_async::<M>().await,
136 #[cfg(feature = "udp")]
137 Self::Udp(connectable) => connectable.connect_async::<M>().await,
138 #[cfg(feature = "direct-serial")]
139 Self::Serial(connectable) => connectable.connect_async::<M>().await,
140 Self::File(connectable) => connectable.connect_async::<M>().await,
141 }
142 }
143}