mavlink_core/async_connection/
mod.rs1use async_trait::async_trait;
2use std::io;
3
4use crate::{
5 connectable::ConnectionAddress, MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message,
6};
7#[cfg(feature = "tcp")]
8mod tcp;
9
10#[cfg(feature = "udp")]
11mod udp;
12
13#[cfg(feature = "direct-serial")]
14mod direct_serial;
15
16mod file;
17
18#[cfg(feature = "signing")]
19use crate::SigningConfig;
20
21#[async_trait::async_trait]
23pub trait AsyncMavConnection<M: Message + Sync + Send> {
24 async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
28
29 async fn recv_raw(&self) -> Result<MAVLinkMessageRaw, crate::error::MessageReadError>;
33
34 async fn send(
36 &self,
37 header: &MavHeader,
38 data: &M,
39 ) -> Result<usize, crate::error::MessageWriteError>;
40
41 fn set_protocol_version(&mut self, version: MavlinkVersion);
43 fn protocol_version(&self) -> MavlinkVersion;
45
46 fn set_allow_recv_any_version(&mut self, allow: bool);
50 fn allow_recv_any_version(&self) -> bool;
52
53 async fn send_frame(
55 &self,
56 frame: &MavFrame<M>,
57 ) -> Result<usize, crate::error::MessageWriteError> {
58 self.send(&frame.header, &frame.msg).await
59 }
60
61 async fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
63 let (header, msg) = self.recv().await?;
64 let protocol_version = self.protocol_version();
65 Ok(MavFrame {
66 header,
67 msg,
68 protocol_version,
69 })
70 }
71
72 async fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
74 let header = MavHeader::default();
75 self.send(&header, data).await
76 }
77
78 #[cfg(feature = "signing")]
80 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
81}
82
83pub async fn connect_async<M: Message + Sync + Send>(
98 address: &str,
99) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
100 ConnectionAddress::parse_address(address)?
101 .connect_async::<M>()
102 .await
103}
104
105#[cfg(any(feature = "tcp", feature = "udp"))]
107pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
108 address: T,
109) -> Result<std::net::SocketAddr, io::Error> {
110 let addr = match address.to_socket_addrs()?.next() {
111 Some(addr) => addr,
112 None => {
113 return Err(io::Error::new(
114 io::ErrorKind::Other,
115 "Host address lookup failed",
116 ));
117 }
118 };
119 Ok(addr)
120}
121
122#[async_trait]
126pub trait AsyncConnectable {
127 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
129 where
130 M: Message + Sync + Send;
131}
132
133#[async_trait]
134impl AsyncConnectable for ConnectionAddress {
135 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
136 where
137 M: Message + Sync + Send,
138 {
139 match self {
140 #[cfg(feature = "tcp")]
141 Self::Tcp(connectable) => connectable.connect_async::<M>().await,
142 #[cfg(feature = "udp")]
143 Self::Udp(connectable) => connectable.connect_async::<M>().await,
144 #[cfg(feature = "direct-serial")]
145 Self::Serial(connectable) => connectable.connect_async::<M>().await,
146 Self::File(connectable) => connectable.connect_async::<M>().await,
147 }
148 }
149}