mavlink_core/connection/
mod.rs

1use crate::{
2    connectable::ConnectionAddress, MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message,
3};
4
5use core::fmt::Display;
6use std::io::{self};
7
8#[cfg(feature = "tcp")]
9pub mod tcp;
10
11#[cfg(feature = "udp")]
12pub mod udp;
13
14#[cfg(feature = "direct-serial")]
15pub mod direct_serial;
16
17#[cfg(feature = "signing")]
18use crate::SigningConfig;
19
20use crate::error::MessageReadError;
21use crate::error::MessageWriteError;
22
23pub mod file;
24
25/// A MAVLink connection
26pub trait MavConnection<M: Message> {
27    /// Receive a MAVLink message.
28    ///
29    /// May blocks until a valid frame is received, ignoring invalid messages.
30    ///
31    /// # Errors
32    ///
33    /// If the connection type blocks until a valid message is received this can not
34    /// return any errors, otherwise return any errors that occured while receiving.  
35    fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
36
37    /// Receive a raw, unparsed MAVLink message.
38    ///
39    /// Blocks until a valid frame is received, ignoring invalid messages.
40    ///
41    /// # Errors
42    ///
43    /// If the connection type blocks until a valid message is received this can not
44    /// return any errors, otherwise return any errors that occured while receiving.  
45    fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>;
46
47    /// Try to receive a MAVLink message.
48    ///
49    /// Non-blocking variant of `recv()`, returns immediately with a `MessageReadError`
50    /// if there is an error or no message is available.
51    ///
52    /// # Errors
53    ///
54    /// Returns any eror encounter while receiving or deserializing a message
55    fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>;
56
57    /// Send a MAVLink message
58    ///
59    /// # Errors
60    ///
61    /// This function will return a [`MessageWriteError::Io`] error when sending fails.
62    fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>;
63
64    /// Sets the MAVLink version to use for receiving (when `allow_recv_any_version()` is `false`) and sending messages.
65    fn set_protocol_version(&mut self, version: MavlinkVersion);
66    /// Gets the currently used MAVLink version
67    fn protocol_version(&self) -> MavlinkVersion;
68
69    /// Set wether MAVLink messages of either version may be received.
70    ///
71    /// If set to false only messages of the version configured with `set_protocol_version()` are received.
72    fn set_allow_recv_any_version(&mut self, allow: bool);
73    /// Wether messages of any MAVLink version may be received
74    fn allow_recv_any_version(&self) -> bool;
75
76    /// Write whole frame
77    ///
78    /// # Errors
79    ///
80    /// This function will return a [`MessageWriteError::Io`] error when sending fails.
81    fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError> {
82        self.send(&frame.header, &frame.msg)
83    }
84
85    /// Read whole frame
86    ///
87    /// # Errors
88    ///
89    /// Returns any eror encounter while receiving or deserializing a message
90    fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> {
91        let (header, msg) = self.recv()?;
92        let protocol_version = self.protocol_version();
93        Ok(MavFrame {
94            header,
95            msg,
96            protocol_version,
97        })
98    }
99
100    /// Send a message with default header
101    ///
102    /// # Errors
103    ///
104    /// This function will return a [`MessageWriteError::Io`] error when sending fails.
105    fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> {
106        let header = MavHeader::default();
107        self.send(&header, data)
108    }
109
110    /// Setup secret key used for message signing, or disable message signing
111    #[cfg(feature = "signing")]
112    fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
113}
114
115/// Connect to a MAVLink node by address string.
116///
117/// The address must be in one of the following formats:
118///
119///  * `tcpin:<addr>:<port>` to create a TCP server, listening an incoming connection
120///  * `tcpout:<addr>:<port>` to create a TCP client
121///  * `udpin:<addr>:<port>` to create a UDP server, listening for incoming packets
122///  * `udpout:<addr>:<port>` to create a UDP client
123///  * `udpbcast:<addr>:<port>` to create a UDP broadcast
124///  * `serial:<port>:<baudrate>` to create a serial connection
125///  * `file:<path>` to extract file data, writing to such a connection does nothing
126///
127/// The type of the connection is determined at runtime based on the address type, so the
128/// connection is returned as a trait object.
129///
130/// # Errors
131///
132/// - [`AddrNotAvailable`] if the address string could not be parsed as a valid MAVLink address
133/// - When the connection could not be established a corresponding [`io::Error`] is returned
134///
135/// [`AddrNotAvailable`]: io::ErrorKind::AddrNotAvailable
136pub fn connect<M: Message + Sync + Send>(
137    address: &str,
138) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
139    ConnectionAddress::parse_address(address)?.connect::<M>()
140}
141
142/// Returns the socket address for the given address.
143#[cfg(any(feature = "tcp", feature = "udp"))]
144pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
145    address: &T,
146) -> Result<std::net::SocketAddr, io::Error> {
147    address
148        .to_socket_addrs()?
149        .next()
150        .ok_or(io::Error::other("Host address lookup failed"))
151}
152
153/// A MAVLink connection address that can be connected to, establishing a [`MavConnection`]
154pub trait Connectable: Display {
155    /// Attempt to establish a blocking MAVLink connection
156    ///
157    /// # Errors
158    ///
159    /// When the connection could not be established a corresponding
160    /// [`io::Error`] is returned
161    fn connect<M: Message>(&self) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>>;
162}
163
164impl Connectable for ConnectionAddress {
165    fn connect<M>(&self) -> std::io::Result<Box<dyn crate::MavConnection<M> + Sync + Send>>
166    where
167        M: Message,
168    {
169        match self {
170            #[cfg(feature = "tcp")]
171            Self::Tcp(config) => config.connect::<M>(),
172            #[cfg(feature = "udp")]
173            Self::Udp(config) => config.connect::<M>(),
174            #[cfg(feature = "direct-serial")]
175            Self::Serial(config) => config.connect::<M>(),
176            Self::File(config) => config.connect::<M>(),
177        }
178    }
179}