mavlink_core/
connectable.rs

1use core::fmt::Display;
2use std::io;
3use std::path::PathBuf;
4
5#[cfg(feature = "direct-serial")]
6use crate::connection::direct_serial::config::SerialConfig;
7use crate::connection::file::config::FileConfig;
8#[cfg(feature = "tcp")]
9use crate::connection::tcp::config::{TcpConfig, TcpMode};
10#[cfg(feature = "udp")]
11use crate::connection::udp::config::{UdpConfig, UdpMode};
12
13/// A parsed MAVLink connection address
14pub enum ConnectionAddress {
15    /// TCP client or server address
16    #[cfg(feature = "tcp")]
17    Tcp(TcpConfig),
18    /// UDP client, server or broadcast address
19    #[cfg(feature = "udp")]
20    Udp(UdpConfig),
21    /// Serial port address
22    #[cfg(feature = "direct-serial")]
23    Serial(SerialConfig),
24    /// File input address
25    File(FileConfig),
26}
27
28#[cfg(feature = "tcp")]
29impl From<TcpConfig> for ConnectionAddress {
30    fn from(value: TcpConfig) -> Self {
31        Self::Tcp(value)
32    }
33}
34
35#[cfg(feature = "udp")]
36impl From<UdpConfig> for ConnectionAddress {
37    fn from(value: UdpConfig) -> Self {
38        Self::Udp(value)
39    }
40}
41
42#[cfg(feature = "direct-serial")]
43impl From<SerialConfig> for ConnectionAddress {
44    fn from(value: SerialConfig) -> Self {
45        Self::Serial(value)
46    }
47}
48
49impl From<FileConfig> for ConnectionAddress {
50    fn from(value: FileConfig) -> Self {
51        Self::File(value)
52    }
53}
54
55impl Display for ConnectionAddress {
56    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
57        match self {
58            #[cfg(feature = "tcp")]
59            Self::Tcp(connectable) => write!(f, "{connectable}"),
60            #[cfg(feature = "udp")]
61            Self::Udp(connectable) => write!(f, "{connectable}"),
62            #[cfg(feature = "direct-serial")]
63            Self::Serial(connectable) => write!(f, "{connectable}"),
64            Self::File(connectable) => write!(f, "{connectable}"),
65        }
66    }
67}
68
69impl ConnectionAddress {
70    /// Parse a MAVLink address string.
71    ///
72    ///  The address must be in one of the following formats:
73    ///
74    ///  * `tcpin:<addr>:<port>` to create a TCP server, listening for an incoming connection
75    ///  * `tcpout:<addr>:<port>` to create a TCP client
76    ///  * `udpin:<addr>:<port>` to create a UDP server, listening for incoming packets
77    ///  * `udpout:<addr>:<port>` to create a UDP client
78    ///  * `udpbcast:<addr>:<port>` to create a UDP broadcast
79    ///  * `serial:<port>:<baudrate>` to create a serial connection
80    ///  * `file:<path>` to extract file data, writing to such a connection does nothing
81    ///
82    /// # Errors
83    ///
84    /// - [`AddrNotAvailable`] if the address string could not be parsed as a valid MAVLink address
85    ///
86    /// [`AddrNotAvailable`]: io::ErrorKind::AddrNotAvailable
87    pub fn parse_address(address: &str) -> Result<Self, io::Error> {
88        let (protocol, address) = address.split_once(':').ok_or(io::Error::new(
89            io::ErrorKind::AddrNotAvailable,
90            "Protocol unsupported",
91        ))?;
92        let conn = match protocol {
93            #[cfg(feature = "direct-serial")]
94            "serial" => {
95                let (port_name, baud) = address.split_once(':').ok_or(io::Error::new(
96                    io::ErrorKind::AddrNotAvailable,
97                    "Incomplete port settings",
98                ))?;
99                Self::Serial(SerialConfig::new(
100                    port_name.to_string(),
101                    baud.parse().map_err(|_| {
102                        io::Error::new(io::ErrorKind::AddrNotAvailable, "Invalid baud rate")
103                    })?,
104                ))
105            }
106            #[cfg(feature = "tcp")]
107            "tcpin" | "tcpout" => {
108                let mode = if protocol == "tcpout" {
109                    TcpMode::TcpOut
110                } else {
111                    TcpMode::TcpIn
112                };
113                Self::Tcp(TcpConfig::new(address.to_string(), mode))
114            }
115            #[cfg(feature = "udp")]
116            "udpin" | "udpout" | "udpcast" => Self::Udp(UdpConfig::new(
117                address.to_string(),
118                match protocol {
119                    "udpin" => UdpMode::Udpin,
120                    "udpout" => UdpMode::Udpout,
121                    "udpcast" => UdpMode::Udpcast,
122                    _ => unreachable!(),
123                },
124            )),
125            "file" => Self::File(FileConfig::new(PathBuf::from(address))),
126            _ => {
127                return Err(io::Error::new(
128                    io::ErrorKind::AddrNotAvailable,
129                    "Protocol unsupported",
130                ))
131            }
132        };
133        Ok(conn)
134    }
135}