mavlink_core/
connectable.rs

1use core::fmt::Display;
2use std::io;
3
4#[derive(Debug, Clone, Copy)]
5pub enum UdpMode {
6    Udpin,
7    Udpout,
8    Udpcast,
9}
10
11#[derive(Debug, Clone)]
12pub struct UdpConnectable {
13    pub(crate) address: String,
14    pub(crate) mode: UdpMode,
15}
16
17impl UdpConnectable {
18    pub fn new(address: String, mode: UdpMode) -> Self {
19        Self { address, mode }
20    }
21}
22impl Display for UdpConnectable {
23    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
24        let mode = match self.mode {
25            UdpMode::Udpin => "udpin",
26            UdpMode::Udpout => "udpout",
27            UdpMode::Udpcast => "udpcast",
28        };
29        write!(f, "{mode}:{}", self.address)
30    }
31}
32
33#[derive(Debug, Clone)]
34pub struct SerialConnectable {
35    pub(crate) port_name: String,
36    pub(crate) baud_rate: usize,
37}
38
39impl SerialConnectable {
40    pub fn new(port_name: String, baud_rate: usize) -> Self {
41        Self {
42            port_name,
43            baud_rate,
44        }
45    }
46}
47impl Display for SerialConnectable {
48    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
49        write!(f, "serial:{}:{}", self.port_name, self.baud_rate)
50    }
51}
52
53#[derive(Debug, Clone)]
54pub struct TcpConnectable {
55    pub(crate) address: String,
56    pub(crate) is_out: bool,
57}
58
59impl TcpConnectable {
60    pub fn new(address: String, is_out: bool) -> Self {
61        Self { address, is_out }
62    }
63}
64impl Display for TcpConnectable {
65    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
66        if self.is_out {
67            write!(f, "tcpout:{}", self.address)
68        } else {
69            write!(f, "tcpin:{}", self.address)
70        }
71    }
72}
73
74#[derive(Debug, Clone)]
75pub struct FileConnectable {
76    pub(crate) address: String,
77}
78
79impl FileConnectable {
80    pub fn new(address: String) -> Self {
81        Self { address }
82    }
83}
84impl Display for FileConnectable {
85    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
86        write!(f, "file:{}", self.address)
87    }
88}
89pub enum ConnectionAddress {
90    #[cfg(feature = "tcp")]
91    Tcp(TcpConnectable),
92    #[cfg(feature = "udp")]
93    Udp(UdpConnectable),
94    #[cfg(feature = "direct-serial")]
95    Serial(SerialConnectable),
96    File(FileConnectable),
97}
98
99impl Display for ConnectionAddress {
100    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
101        match self {
102            #[cfg(feature = "tcp")]
103            Self::Tcp(connectable) => write!(f, "{connectable}"),
104            #[cfg(feature = "udp")]
105            Self::Udp(connectable) => write!(f, "{connectable}"),
106            #[cfg(feature = "direct-serial")]
107            Self::Serial(connectable) => write!(f, "{connectable}"),
108            Self::File(connectable) => write!(f, "{connectable}"),
109        }
110    }
111}
112
113impl ConnectionAddress {
114    pub fn parse_address(address: &str) -> Result<Self, io::Error> {
115        let (protocol, address) = address.split_once(':').ok_or(io::Error::new(
116            io::ErrorKind::AddrNotAvailable,
117            "Protocol unsupported",
118        ))?;
119        let conn = match protocol {
120            #[cfg(feature = "direct-serial")]
121            "serial" => {
122                let (port_name, baud) = address.split_once(':').ok_or(io::Error::new(
123                    io::ErrorKind::AddrNotAvailable,
124                    "Incomplete port settings",
125                ))?;
126                Self::Serial(SerialConnectable::new(
127                    port_name.to_string(),
128                    baud.parse().map_err(|_| {
129                        io::Error::new(io::ErrorKind::AddrNotAvailable, "Invalid baud rate")
130                    })?,
131                ))
132            }
133            #[cfg(feature = "tcp")]
134            "tcpin" | "tcpout" => Self::Tcp(TcpConnectable::new(
135                address.to_string(),
136                protocol == "tcpout",
137            )),
138            #[cfg(feature = "udp")]
139            "udpin" | "udpout" | "udpcast" => Self::Udp(UdpConnectable::new(
140                address.to_string(),
141                match protocol {
142                    "udpin" => UdpMode::Udpin,
143                    "udpout" => UdpMode::Udpout,
144                    "udpcast" => UdpMode::Udpcast,
145                    _ => unreachable!(),
146                },
147            )),
148            "file" => Self::File(FileConnectable::new(address.to_string())),
149            _ => {
150                return Err(io::Error::new(
151                    io::ErrorKind::AddrNotAvailable,
152                    "Protocol unsupported",
153                ))
154            }
155        };
156        Ok(conn)
157    }
158}