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    Tcp(TcpConnectable),
91    Udp(UdpConnectable),
92    Serial(SerialConnectable),
93    File(FileConnectable),
94}
95
96impl Display for ConnectionAddress {
97    fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
98        match self {
99            Self::Tcp(connectable) => write!(f, "{connectable}"),
100            Self::Udp(connectable) => write!(f, "{connectable}"),
101            Self::Serial(connectable) => write!(f, "{connectable}"),
102            Self::File(connectable) => write!(f, "{connectable}"),
103        }
104    }
105}
106
107impl ConnectionAddress {
108    pub fn parse_address(address: &str) -> Result<Self, io::Error> {
109        let (protocol, address) = address.split_once(':').ok_or(io::Error::new(
110            io::ErrorKind::AddrNotAvailable,
111            "Protocol unsupported",
112        ))?;
113        let conn = match protocol {
114            #[cfg(feature = "direct-serial")]
115            "serial" => {
116                let (port_name, baud) = address.split_once(':').ok_or(io::Error::new(
117                    io::ErrorKind::AddrNotAvailable,
118                    "Incomplete port settings",
119                ))?;
120                Self::Serial(SerialConnectable::new(
121                    port_name.to_string(),
122                    baud.parse().map_err(|_| {
123                        io::Error::new(io::ErrorKind::AddrNotAvailable, "Invalid baud rate")
124                    })?,
125                ))
126            }
127            #[cfg(feature = "tcp")]
128            "tcpin" | "tcpout" => Self::Tcp(TcpConnectable::new(
129                address.to_string(),
130                protocol == "tcpout",
131            )),
132            #[cfg(feature = "udp")]
133            "udpin" | "udpout" | "udpcast" => Self::Udp(UdpConnectable::new(
134                address.to_string(),
135                match protocol {
136                    "udpin" => UdpMode::Udpin,
137                    "udpout" => UdpMode::Udpout,
138                    "udpcast" => UdpMode::Udpcast,
139                    _ => unreachable!(),
140                },
141            )),
142            "file" => Self::File(FileConnectable::new(address.to_string())),
143            _ => {
144                return Err(io::Error::new(
145                    io::ErrorKind::AddrNotAvailable,
146                    "Protocol unsupported",
147                ))
148            }
149        };
150        Ok(conn)
151    }
152}