mavlink_core/connection/
mod.rs

1#[cfg(feature = "tcp")]
2pub mod tcp;
3
4#[cfg(feature = "udp")]
5pub mod udp;
6
7#[cfg(feature = "direct-serial")]
8pub mod direct_serial;
9
10pub mod file;
11
12use core::fmt::Display;
13use core::marker::PhantomData;
14use std::io::{self};
15
16#[cfg(feature = "tcp")]
17use self::tcp::TcpConnection;
18
19#[cfg(feature = "udp")]
20use self::udp::UdpConnection;
21
22#[cfg(feature = "direct-serial")]
23use self::direct_serial::SerialConnection;
24
25use self::file::FileConnection;
26
27#[cfg(feature = "signing")]
28use crate::SigningConfig;
29
30use crate::error::MessageReadError;
31use crate::error::MessageWriteError;
32use crate::{
33    connectable::ConnectionAddress, MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message,
34};
35
36/// A MAVLink connection
37pub trait MavConnection<M: Message> {
38    /// Receive a MAVLink message.
39    ///
40    /// May blocks until a valid frame is received, ignoring invalid messages.
41    ///
42    /// # Errors
43    ///
44    /// If the connection type blocks until a valid message is received this can not
45    /// return any errors, otherwise return any errors that occured while receiving.
46    fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
47
48    /// Receive a raw, unparsed MAVLink message.
49    ///
50    /// Blocks until a valid frame is received, ignoring invalid messages.
51    ///
52    /// # Errors
53    ///
54    /// If the connection type blocks until a valid message is received this can not
55    /// return any errors, otherwise return any errors that occured while receiving.
56    fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>;
57
58    /// Try to receive a MAVLink message.
59    ///
60    /// Non-blocking variant of `recv()`, returns immediately with a `MessageReadError`
61    /// if there is an error or no message is available.
62    ///
63    /// # Errors
64    ///
65    /// Returns any eror encounter while receiving or deserializing a message
66    fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>;
67
68    /// Send a MAVLink message
69    ///
70    /// # Errors
71    ///
72    /// This function will return a [`MessageWriteError::Io`] error when sending fails.
73    fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>;
74
75    /// Sets the MAVLink version to use for receiving (when `allow_recv_any_version()` is `false`) and sending messages.
76    fn set_protocol_version(&mut self, version: MavlinkVersion);
77    /// Gets the currently used MAVLink version
78    fn protocol_version(&self) -> MavlinkVersion;
79
80    /// Set wether MAVLink messages of either version may be received.
81    ///
82    /// If set to false only messages of the version configured with `set_protocol_version()` are received.
83    fn set_allow_recv_any_version(&mut self, allow: bool);
84    /// Wether messages of any MAVLink version may be received
85    fn allow_recv_any_version(&self) -> bool;
86
87    /// Write whole frame
88    ///
89    /// # Errors
90    ///
91    /// This function will return a [`MessageWriteError::Io`] error when sending fails.
92    fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError> {
93        self.send(&frame.header, &frame.msg)
94    }
95
96    /// Read whole frame
97    ///
98    /// # Errors
99    ///
100    /// Returns any eror encounter while receiving or deserializing a message
101    fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> {
102        let (header, msg) = self.recv()?;
103        let protocol_version = self.protocol_version();
104        Ok(MavFrame {
105            header,
106            msg,
107            protocol_version,
108        })
109    }
110
111    /// Send a message with default header
112    ///
113    /// # Errors
114    ///
115    /// This function will return a [`MessageWriteError::Io`] error when sending fails.
116    fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> {
117        let header = MavHeader::default();
118        self.send(&header, data)
119    }
120
121    /// Setup secret key used for message signing, or disable message signing
122    #[cfg(feature = "signing")]
123    fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
124}
125
126/// Concrete MAVLink connection returned by [`connect`].
127pub struct Connection<M: Message> {
128    inner: ConnectionInner,
129    _p: PhantomData<M>,
130}
131
132enum ConnectionInner {
133    #[cfg(feature = "tcp")]
134    Tcp(TcpConnection),
135    #[cfg(feature = "udp")]
136    Udp(UdpConnection),
137    #[cfg(feature = "direct-serial")]
138    Serial(SerialConnection),
139    File(FileConnection),
140}
141
142impl<M: Message> Connection<M> {
143    fn new(inner: ConnectionInner) -> Self {
144        Self {
145            inner,
146            _p: PhantomData,
147        }
148    }
149}
150
151#[cfg(feature = "tcp")]
152impl<M: Message> From<TcpConnection> for Connection<M> {
153    fn from(value: TcpConnection) -> Self {
154        Self::new(ConnectionInner::Tcp(value))
155    }
156}
157
158#[cfg(feature = "udp")]
159impl<M: Message> From<UdpConnection> for Connection<M> {
160    fn from(value: UdpConnection) -> Self {
161        Self::new(ConnectionInner::Udp(value))
162    }
163}
164
165#[cfg(feature = "direct-serial")]
166impl<M: Message> From<SerialConnection> for Connection<M> {
167    fn from(value: SerialConnection) -> Self {
168        Self::new(ConnectionInner::Serial(value))
169    }
170}
171
172impl<M: Message> From<FileConnection> for Connection<M> {
173    fn from(value: FileConnection) -> Self {
174        Self::new(ConnectionInner::File(value))
175    }
176}
177
178impl<M: Message> MavConnection<M> for Connection<M> {
179    fn recv(&self) -> Result<(MavHeader, M), MessageReadError> {
180        match &self.inner {
181            #[cfg(feature = "tcp")]
182            ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv(conn),
183            #[cfg(feature = "udp")]
184            ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv(conn),
185            #[cfg(feature = "direct-serial")]
186            ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv(conn),
187            ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv(conn),
188        }
189    }
190
191    fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError> {
192        match &self.inner {
193            #[cfg(feature = "tcp")]
194            ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv_raw(conn),
195            #[cfg(feature = "udp")]
196            ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv_raw(conn),
197            #[cfg(feature = "direct-serial")]
198            ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv_raw(conn),
199            ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv_raw(conn),
200        }
201    }
202
203    fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError> {
204        match &self.inner {
205            #[cfg(feature = "tcp")]
206            ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::try_recv(conn),
207            #[cfg(feature = "udp")]
208            ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::try_recv(conn),
209            #[cfg(feature = "direct-serial")]
210            ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::try_recv(conn),
211            ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::try_recv(conn),
212        }
213    }
214
215    fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError> {
216        match &self.inner {
217            #[cfg(feature = "tcp")]
218            ConnectionInner::Tcp(conn) => {
219                <TcpConnection as MavConnection<M>>::send(conn, header, data)
220            }
221            #[cfg(feature = "udp")]
222            ConnectionInner::Udp(conn) => {
223                <UdpConnection as MavConnection<M>>::send(conn, header, data)
224            }
225            #[cfg(feature = "direct-serial")]
226            ConnectionInner::Serial(conn) => {
227                <SerialConnection as MavConnection<M>>::send(conn, header, data)
228            }
229            ConnectionInner::File(conn) => {
230                <FileConnection as MavConnection<M>>::send(conn, header, data)
231            }
232        }
233    }
234
235    fn set_protocol_version(&mut self, version: MavlinkVersion) {
236        match &mut self.inner {
237            #[cfg(feature = "tcp")]
238            ConnectionInner::Tcp(conn) => {
239                <TcpConnection as MavConnection<M>>::set_protocol_version(conn, version);
240            }
241            #[cfg(feature = "udp")]
242            ConnectionInner::Udp(conn) => {
243                <UdpConnection as MavConnection<M>>::set_protocol_version(conn, version);
244            }
245            #[cfg(feature = "direct-serial")]
246            ConnectionInner::Serial(conn) => {
247                <SerialConnection as MavConnection<M>>::set_protocol_version(conn, version);
248            }
249            ConnectionInner::File(conn) => {
250                <FileConnection as MavConnection<M>>::set_protocol_version(conn, version);
251            }
252        }
253    }
254
255    fn protocol_version(&self) -> MavlinkVersion {
256        match &self.inner {
257            #[cfg(feature = "tcp")]
258            ConnectionInner::Tcp(conn) => {
259                <TcpConnection as MavConnection<M>>::protocol_version(conn)
260            }
261            #[cfg(feature = "udp")]
262            ConnectionInner::Udp(conn) => {
263                <UdpConnection as MavConnection<M>>::protocol_version(conn)
264            }
265            #[cfg(feature = "direct-serial")]
266            ConnectionInner::Serial(conn) => {
267                <SerialConnection as MavConnection<M>>::protocol_version(conn)
268            }
269            ConnectionInner::File(conn) => {
270                <FileConnection as MavConnection<M>>::protocol_version(conn)
271            }
272        }
273    }
274
275    fn set_allow_recv_any_version(&mut self, allow: bool) {
276        match &mut self.inner {
277            #[cfg(feature = "tcp")]
278            ConnectionInner::Tcp(conn) => {
279                <TcpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
280            }
281            #[cfg(feature = "udp")]
282            ConnectionInner::Udp(conn) => {
283                <UdpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
284            }
285            #[cfg(feature = "direct-serial")]
286            ConnectionInner::Serial(conn) => {
287                <SerialConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
288            }
289            ConnectionInner::File(conn) => {
290                <FileConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
291            }
292        }
293    }
294
295    fn allow_recv_any_version(&self) -> bool {
296        match &self.inner {
297            #[cfg(feature = "tcp")]
298            ConnectionInner::Tcp(conn) => {
299                <TcpConnection as MavConnection<M>>::allow_recv_any_version(conn)
300            }
301            #[cfg(feature = "udp")]
302            ConnectionInner::Udp(conn) => {
303                <UdpConnection as MavConnection<M>>::allow_recv_any_version(conn)
304            }
305            #[cfg(feature = "direct-serial")]
306            ConnectionInner::Serial(conn) => {
307                <SerialConnection as MavConnection<M>>::allow_recv_any_version(conn)
308            }
309            ConnectionInner::File(conn) => {
310                <FileConnection as MavConnection<M>>::allow_recv_any_version(conn)
311            }
312        }
313    }
314
315    #[cfg(feature = "signing")]
316    fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
317        let mut signing_data = signing_data;
318        match &mut self.inner {
319            #[cfg(feature = "tcp")]
320            ConnectionInner::Tcp(conn) => {
321                <TcpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
322            }
323            #[cfg(feature = "udp")]
324            ConnectionInner::Udp(conn) => {
325                <UdpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
326            }
327            #[cfg(feature = "direct-serial")]
328            ConnectionInner::Serial(conn) => {
329                <SerialConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
330            }
331            ConnectionInner::File(conn) => {
332                <FileConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
333            }
334        }
335    }
336}
337
338/// Connect to a MAVLink node by address string.
339///
340/// The address must be in one of the following formats:
341///
342///  * `tcpin:<addr>:<port>` to create a TCP server, listening an incoming connection
343///  * `tcpout:<addr>:<port>` to create a TCP client
344///  * `udpin:<addr>:<port>` to create a UDP server, listening for incoming packets
345///  * `udpout:<addr>:<port>` to create a UDP client
346///  * `udpbcast:<addr>:<port>` to create a UDP broadcast
347///  * `serial:<port>:<baudrate>` to create a serial connection
348///  * `file:<path>` to extract file data, writing to such a connection does nothing
349///
350/// The type of the connection is determined at runtime based on the address type
351/// and the resulting [`Connection`] enum stores the concrete transport.
352///
353/// # Errors
354///
355/// - [`AddrNotAvailable`] if the address string could not be parsed as a valid MAVLink address
356/// - When the connection could not be established a corresponding [`io::Error`] is returned
357///
358/// [`AddrNotAvailable`]: io::ErrorKind::AddrNotAvailable
359pub fn connect<M: Message + Sync + Send>(address: &str) -> io::Result<Connection<M>> {
360    ConnectionAddress::parse_address(address)?.connect::<M>()
361}
362
363/// Returns the socket address for the given address.
364#[cfg(any(feature = "tcp", feature = "udp"))]
365pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
366    address: &T,
367) -> Result<std::net::SocketAddr, io::Error> {
368    address
369        .to_socket_addrs()?
370        .next()
371        .ok_or(io::Error::other("Host address lookup failed"))
372}
373
374/// A MAVLink connection address that can be connected to, establishing a [`MavConnection`]
375pub trait Connectable: Display {
376    /// Attempt to establish a blocking MAVLink connection
377    ///
378    /// # Errors
379    ///
380    /// When the connection could not be established a corresponding
381    /// [`io::Error`] is returned
382    fn connect<M: Message>(&self) -> io::Result<Connection<M>>;
383}
384
385impl Connectable for ConnectionAddress {
386    fn connect<M>(&self) -> std::io::Result<Connection<M>>
387    where
388        M: Message,
389    {
390        match self {
391            #[cfg(feature = "tcp")]
392            Self::Tcp(config) => config.connect::<M>(),
393            #[cfg(feature = "udp")]
394            Self::Udp(config) => config.connect::<M>(),
395            #[cfg(feature = "direct-serial")]
396            Self::Serial(config) => config.connect::<M>(),
397            Self::File(config) => config.connect::<M>(),
398        }
399    }
400}