mavlink_core/
connectable.rs1use core::fmt::Display;
2use std::io;
3
4#[derive(Debug, Clone, Copy)]
6pub enum UdpMode {
7 Udpin,
9 Udpout,
11 Udpcast,
13}
14
15#[derive(Debug, Clone)]
17pub struct UdpConnectable {
18 pub(crate) address: String,
19 pub(crate) mode: UdpMode,
20}
21
22impl UdpConnectable {
23 pub fn new(address: String, mode: UdpMode) -> Self {
27 Self { address, mode }
28 }
29}
30impl Display for UdpConnectable {
31 fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
32 let mode = match self.mode {
33 UdpMode::Udpin => "udpin",
34 UdpMode::Udpout => "udpout",
35 UdpMode::Udpcast => "udpcast",
36 };
37 write!(f, "{mode}:{}", self.address)
38 }
39}
40
41#[derive(Debug, Clone)]
43pub struct SerialConnectable {
44 pub(crate) port_name: String,
45 pub(crate) baud_rate: usize,
46}
47
48impl SerialConnectable {
49 pub fn new(port_name: String, baud_rate: usize) -> Self {
51 Self {
52 port_name,
53 baud_rate,
54 }
55 }
56}
57impl Display for SerialConnectable {
58 fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
59 write!(f, "serial:{}:{}", self.port_name, self.baud_rate)
60 }
61}
62
63#[derive(Debug, Clone)]
65pub struct TcpConnectable {
66 pub(crate) address: String,
67 pub(crate) is_out: bool,
68}
69
70impl TcpConnectable {
71 pub fn new(address: String, is_out: bool) -> Self {
76 Self { address, is_out }
77 }
78}
79impl Display for TcpConnectable {
80 fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
81 if self.is_out {
82 write!(f, "tcpout:{}", self.address)
83 } else {
84 write!(f, "tcpin:{}", self.address)
85 }
86 }
87}
88
89#[derive(Debug, Clone)]
91pub struct FileConnectable {
92 pub(crate) address: String,
93}
94
95impl FileConnectable {
96 pub fn new(address: String) -> Self {
98 Self { address }
99 }
100}
101impl Display for FileConnectable {
102 fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
103 write!(f, "file:{}", self.address)
104 }
105}
106
107pub enum ConnectionAddress {
109 #[cfg(feature = "tcp")]
111 Tcp(TcpConnectable),
112 #[cfg(feature = "udp")]
114 Udp(UdpConnectable),
115 #[cfg(feature = "direct-serial")]
117 Serial(SerialConnectable),
118 File(FileConnectable),
120}
121
122impl Display for ConnectionAddress {
123 fn fmt(&self, f: &mut core::fmt::Formatter<'_>) -> core::fmt::Result {
124 match self {
125 #[cfg(feature = "tcp")]
126 Self::Tcp(connectable) => write!(f, "{connectable}"),
127 #[cfg(feature = "udp")]
128 Self::Udp(connectable) => write!(f, "{connectable}"),
129 #[cfg(feature = "direct-serial")]
130 Self::Serial(connectable) => write!(f, "{connectable}"),
131 Self::File(connectable) => write!(f, "{connectable}"),
132 }
133 }
134}
135
136impl ConnectionAddress {
137 pub fn parse_address(address: &str) -> Result<Self, io::Error> {
149 let (protocol, address) = address.split_once(':').ok_or(io::Error::new(
150 io::ErrorKind::AddrNotAvailable,
151 "Protocol unsupported",
152 ))?;
153 let conn = match protocol {
154 #[cfg(feature = "direct-serial")]
155 "serial" => {
156 let (port_name, baud) = address.split_once(':').ok_or(io::Error::new(
157 io::ErrorKind::AddrNotAvailable,
158 "Incomplete port settings",
159 ))?;
160 Self::Serial(SerialConnectable::new(
161 port_name.to_string(),
162 baud.parse().map_err(|_| {
163 io::Error::new(io::ErrorKind::AddrNotAvailable, "Invalid baud rate")
164 })?,
165 ))
166 }
167 #[cfg(feature = "tcp")]
168 "tcpin" | "tcpout" => Self::Tcp(TcpConnectable::new(
169 address.to_string(),
170 protocol == "tcpout",
171 )),
172 #[cfg(feature = "udp")]
173 "udpin" | "udpout" | "udpcast" => Self::Udp(UdpConnectable::new(
174 address.to_string(),
175 match protocol {
176 "udpin" => UdpMode::Udpin,
177 "udpout" => UdpMode::Udpout,
178 "udpcast" => UdpMode::Udpcast,
179 _ => unreachable!(),
180 },
181 )),
182 "file" => Self::File(FileConnectable::new(address.to_string())),
183 _ => {
184 return Err(io::Error::new(
185 io::ErrorKind::AddrNotAvailable,
186 "Protocol unsupported",
187 ))
188 }
189 };
190 Ok(conn)
191 }
192}