Skip to main content

mavlink_core/async_connection/
mod.rs

1use 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/// An async MAVLink connection
22#[async_trait::async_trait]
23pub trait AsyncMavConnection<M: Message + Sync + Send> {
24    /// Receive a mavlink message.
25    ///
26    /// Yield until a valid frame is received, ignoring invalid messages.
27    async fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
28
29    /// Receive a raw, unparsed mavlink message.
30    ///
31    /// Yield until a valid frame is received, ignoring invalid messages.
32    async fn recv_raw(&self) -> Result<MAVLinkMessageRaw, crate::error::MessageReadError>;
33
34    /// Try to receive a MAVLink message.
35    ///
36    /// Non-blocking variant of `recv()`, returns immediately with a `MessageReadError`
37    /// if there is an error or no message is available.
38    ///
39    /// # Errors
40    ///
41    /// Returns any eror encounter while receiving or deserializing a message.
42    async fn try_recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
43
44    /// Send a mavlink message
45    async fn send(
46        &self,
47        header: &MavHeader,
48        data: &M,
49    ) -> Result<usize, crate::error::MessageWriteError>;
50
51    /// Sets the MAVLink version to use for receiving (when `allow_recv_any_version()` is `false`) and sending messages.
52    fn set_protocol_version(&mut self, version: MavlinkVersion);
53    /// Gets the currently used MAVLink version
54    fn protocol_version(&self) -> MavlinkVersion;
55
56    /// Set wether MAVLink messages of either version may be received.
57    ///
58    /// If set to false only messages of the version configured with `set_protocol_version()` are received.
59    fn set_allow_recv_any_version(&mut self, allow: bool);
60
61    /// Wether messages of any MAVLink version may be received.
62    fn allow_recv_any_version(&self) -> bool;
63
64    /// Write whole frame.
65    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    /// Read whole frame.
73    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    /// Send a message with default header.
84    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    /// Setup secret key used for message signing, or disable message signing.
90    #[cfg(feature = "mav2-message-signing")]
91    fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
92}
93
94/// Connect asynchronously to a MAVLink node by address string.
95///
96/// The address must be in one of the following formats:
97///
98///  * `tcpin:<addr>:<port>` to create a TCP server, listening for an incoming connection
99///  * `tcpout:<addr>:<port>` to create a TCP client
100///  * `udpin:<addr>:<port>` to create a UDP server, listening for incoming packets
101///  * `udpout:<addr>:<port>` to create a UDP client
102///  * `udpbcast:<addr>:<port>` to create a UDP broadcast
103///  * `serial:<port>:<baudrate>` to create a serial connection
104///  * `file:<path>` to extract file data, writing to such a connection does nothing
105///
106/// The type of the connection is determined at runtime based on the address type, so the
107/// connection is returned as a trait object.
108///
109/// # Errors
110///
111/// - [`AddrNotAvailable`] if the address string could not be parsed as a valid MAVLink address
112/// - When the connection could not be established a corresponding [`io::Error`] is returned
113///
114/// [`AddrNotAvailable`]: io::ErrorKind::AddrNotAvailable
115pub 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/// Returns the socket address for the given address.
124#[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/// A MAVLink connection address that can be connected to, establishing an [`AsyncMavConnection`]
138///
139/// This is the `async` version of `Connectable`.
140#[async_trait]
141pub trait AsyncConnectable {
142    /// Attempt to establish an asynchronous MAVLink connection
143    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}