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 = "transport-tcp")]
8mod tcp;
9
10#[cfg(feature = "transport-udp")]
11mod udp;
12
13#[cfg(feature = "transport-direct-serial")]
14mod direct_serial;
15
16mod file;
17
18#[cfg(feature = "mav2-message-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 try_recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
43
44 async fn send(
46 &self,
47 header: &MavHeader,
48 data: &M,
49 ) -> Result<usize, crate::error::MessageWriteError>;
50
51 fn set_protocol_version(&mut self, version: MavlinkVersion);
53 fn protocol_version(&self) -> MavlinkVersion;
55
56 fn set_allow_recv_any_version(&mut self, allow: bool);
60
61 fn allow_recv_any_version(&self) -> bool;
63
64 async fn send_frame(
66 &self,
67 frame: &MavFrame<M>,
68 ) -> Result<usize, crate::error::MessageWriteError> {
69 self.send(&frame.header, &frame.msg).await
70 }
71
72 async fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
74 let (header, msg) = self.recv().await?;
75 let protocol_version = self.protocol_version();
76 Ok(MavFrame {
77 header,
78 msg,
79 protocol_version,
80 })
81 }
82
83 async fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
85 let header = MavHeader::default();
86 self.send(&header, data).await
87 }
88
89 #[cfg(feature = "mav2-message-signing")]
91 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
92}
93
94pub async fn connect_async<M: Message + Sync + Send>(
116 address: &str,
117) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
118 ConnectionAddress::parse_address(address)?
119 .connect_async::<M>()
120 .await
121}
122
123#[cfg(any(feature = "transport-tcp", feature = "transport-udp"))]
125pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
126 address: T,
127) -> Result<std::net::SocketAddr, io::Error> {
128 let addr = match address.to_socket_addrs()?.next() {
129 Some(addr) => addr,
130 None => {
131 return Err(io::Error::other("Host address lookup failed"));
132 }
133 };
134 Ok(addr)
135}
136
137#[async_trait]
141pub trait AsyncConnectable {
142 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
144 where
145 M: Message + Sync + Send;
146}
147
148#[async_trait]
149impl AsyncConnectable for ConnectionAddress {
150 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
151 where
152 M: Message + Sync + Send,
153 {
154 match self {
155 #[cfg(feature = "transport-tcp")]
156 Self::Tcp(connectable) => connectable.connect_async::<M>().await,
157 #[cfg(feature = "transport-udp")]
158 Self::Udp(connectable) => connectable.connect_async::<M>().await,
159 #[cfg(feature = "transport-direct-serial")]
160 Self::Serial(connectable) => connectable.connect_async::<M>().await,
161 Self::File(connectable) => connectable.connect_async::<M>().await,
162 }
163 }
164}