mavlink_core/connection/async.rs
1use std::io;
2
3use async_trait::async_trait;
4
5#[cfg(feature = "mav2-message-signing")]
6use crate::SigningConfig;
7
8use crate::error::MessageReadError;
9use crate::error::MessageWriteError;
10use crate::{
11 MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message, connectable::ConnectionAddress,
12};
13
14/// An async MAVLink connection
15#[async_trait]
16pub trait AsyncMavConnection<M: Message + Sync + Send> {
17 /// Receive a mavlink message.
18 ///
19 /// Yield until a valid frame is received, ignoring invalid messages.
20 async fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
21
22 /// Receive a raw, unparsed mavlink message.
23 ///
24 /// Yield until a valid frame is received, ignoring invalid messages.
25 async fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>;
26
27 /// Try to receive a MAVLink message.
28 ///
29 /// Non-blocking variant of `recv()`, returns immediately with a `MessageReadError`
30 /// if there is an error or no message is available.
31 ///
32 /// # Errors
33 ///
34 /// Returns any eror encounter while receiving or deserializing a message.
35 async fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>;
36
37 /// Send a mavlink message
38 async fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>;
39
40 /// Sets the MAVLink version to use for receiving (when `allow_recv_any_version()` is `false`) and sending messages.
41 fn set_protocol_version(&mut self, version: MavlinkVersion);
42 /// Gets the currently used MAVLink version
43 fn protocol_version(&self) -> MavlinkVersion;
44
45 /// Set wether MAVLink messages of either version may be received.
46 ///
47 /// If set to false only messages of the version configured with `set_protocol_version()` are received.
48 fn set_allow_recv_any_version(&mut self, allow: bool);
49
50 /// Wether messages of any MAVLink version may be received.
51 fn allow_recv_any_version(&self) -> bool;
52
53 /// Write whole frame.
54 async fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError> {
55 self.send(&frame.header, &frame.msg).await
56 }
57
58 /// Read whole frame.
59 async fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> {
60 let (header, msg) = self.recv().await?;
61 let protocol_version = self.protocol_version();
62 Ok(MavFrame {
63 header,
64 msg,
65 protocol_version,
66 })
67 }
68
69 /// Send a message with default header.
70 async fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> {
71 let header = MavHeader::default();
72 self.send(&header, data).await
73 }
74
75 /// Setup secret key used for message signing, or disable message signing.
76 #[cfg(feature = "mav2-message-signing")]
77 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
78}
79
80/// Connect asynchronously to a MAVLink node by address string.
81///
82/// The address must be in one of the following formats:
83///
84/// * `tcpin:<addr>:<port>` to create a TCP server, listening for an incoming connection
85/// * `tcpout:<addr>:<port>` to create a TCP client
86/// * `udpin:<addr>:<port>` to create a UDP server, listening for incoming packets
87/// * `udpout:<addr>:<port>` to create a UDP client
88/// * `udpbcast:<addr>:<port>` to create a UDP broadcast
89/// * `serial:<port>:<baudrate>` to create a serial connection
90/// * `file:<path>` to extract file data, writing to such a connection does nothing
91///
92/// The type of the connection is determined at runtime based on the address type, so the
93/// connection is returned as a trait object.
94///
95/// # Errors
96///
97/// - [`AddrNotAvailable`] if the address string could not be parsed as a valid MAVLink address
98/// - When the connection could not be established a corresponding [`io::Error`] is returned
99///
100/// [`AddrNotAvailable`]: io::ErrorKind::AddrNotAvailable
101pub async fn connect_async<M: Message + Sync + Send>(
102 address: &str,
103) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>> {
104 ConnectionAddress::parse_address(address)?
105 .connect_async::<M>()
106 .await
107}
108
109/// A MAVLink connection address that can be connected to, establishing an [`AsyncMavConnection`]
110///
111/// This is the `async` version of `Connectable`.
112#[async_trait]
113pub trait AsyncConnectable {
114 /// Attempt to establish an asynchronous MAVLink connection
115 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
116 where
117 M: Message + Sync + Send;
118}
119
120#[async_trait]
121impl AsyncConnectable for ConnectionAddress {
122 async fn connect_async<M>(&self) -> io::Result<Box<dyn AsyncMavConnection<M> + Sync + Send>>
123 where
124 M: Message + Sync + Send,
125 {
126 match self {
127 #[cfg(feature = "transport-tcp")]
128 Self::Tcp(connectable) => connectable.connect_async::<M>().await,
129 #[cfg(feature = "transport-udp")]
130 Self::Udp(connectable) => connectable.connect_async::<M>().await,
131 #[cfg(feature = "transport-direct-serial")]
132 Self::Serial(connectable) => connectable.connect_async::<M>().await,
133 Self::File(connectable) => connectable.connect_async::<M>().await,
134 }
135 }
136}