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);
36 fn get_protocol_version(&self) -> MavlinkVersion;
37
38 async fn send_frame(
40 &self,
41 frame: &MavFrame<M>,
42 ) -> Result<usize, crate::error::MessageWriteError> {
43 self.send(&frame.header, &frame.msg).await
44 }
45
46 async fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
48 let (header, msg) = self.recv().await?;
49 let protocol_version = self.get_protocol_version();
50 Ok(MavFrame {
51 header,
52 msg,
53 protocol_version,
54 })
55 }
56
57 async fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
59 let header = MavHeader::default();
60 self.send(&header, data).await
61 }
62
63 #[cfg(feature = "signing")]
65 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
66}
67
68pub async fn connect_async<M: Message + Sync + Send>(
83 address: &str,
84) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
85 ConnectionAddress::parse_address(address)?
86 .connect_async::<M>()
87 .await
88}
89
90pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
92 address: T,
93) -> Result<std::net::SocketAddr, io::Error> {
94 let addr = match address.to_socket_addrs()?.next() {
95 Some(addr) => addr,
96 None => {
97 return Err(io::Error::new(
98 io::ErrorKind::Other,
99 "Host address lookup failed",
100 ));
101 }
102 };
103 Ok(addr)
104}
105
106#[async_trait]
107pub 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]
114impl 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}