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>(
105    address: &str,
106) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
107    ConnectionAddress::parse_address(address)?
108        .connect_async::<M>()
109        .await
110}
111
112#[cfg(any(feature = "tcp", feature = "udp"))]
114pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
115    address: T,
116) -> Result<std::net::SocketAddr, io::Error> {
117    let addr = match address.to_socket_addrs()?.next() {
118        Some(addr) => addr,
119        None => {
120            return Err(io::Error::other("Host address lookup failed"));
121        }
122    };
123    Ok(addr)
124}
125
126#[async_trait]
130pub trait AsyncConnectable {
131    async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
133    where
134        M: Message + Sync + Send;
135}
136
137#[async_trait]
138impl AsyncConnectable for ConnectionAddress {
139    async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
140    where
141        M: Message + Sync + Send,
142    {
143        match self {
144            #[cfg(feature = "tcp")]
145            Self::Tcp(connectable) => connectable.connect_async::<M>().await,
146            #[cfg(feature = "udp")]
147            Self::Udp(connectable) => connectable.connect_async::<M>().await,
148            #[cfg(feature = "direct-serial")]
149            Self::Serial(connectable) => connectable.connect_async::<M>().await,
150            Self::File(connectable) => connectable.connect_async::<M>().await,
151        }
152    }
153}