1#[cfg(feature = "transport-tcp")]
2pub mod tcp;
3
4#[cfg(feature = "transport-udp")]
5pub mod udp;
6
7#[cfg(feature = "transport-direct-serial")]
8pub mod direct_serial;
9
10pub mod file;
11
12use core::fmt::Display;
13use core::marker::PhantomData;
14use std::io::{self};
15
16#[cfg(feature = "transport-tcp")]
17use self::tcp::TcpConnection;
18
19#[cfg(feature = "transport-udp")]
20use self::udp::UdpConnection;
21
22#[cfg(feature = "transport-direct-serial")]
23use self::direct_serial::SerialConnection;
24
25use self::file::FileConnection;
26
27#[cfg(feature = "mav2-message-signing")]
28use crate::SigningConfig;
29
30use crate::error::MessageReadError;
31use crate::error::MessageWriteError;
32use crate::{
33 connectable::ConnectionAddress, MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message,
34};
35
36pub trait MavConnection<M: Message> {
38 fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
47
48 fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>;
57
58 fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>;
67
68 fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>;
74
75 fn set_protocol_version(&mut self, version: MavlinkVersion);
77 fn protocol_version(&self) -> MavlinkVersion;
79
80 fn set_allow_recv_any_version(&mut self, allow: bool);
84
85 fn allow_recv_any_version(&self) -> bool;
87
88 fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError> {
94 self.send(&frame.header, &frame.msg)
95 }
96
97 fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> {
103 let (header, msg) = self.recv()?;
104 let protocol_version = self.protocol_version();
105 Ok(MavFrame {
106 header,
107 msg,
108 protocol_version,
109 })
110 }
111
112 fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> {
118 let header = MavHeader::default();
119 self.send(&header, data)
120 }
121
122 #[cfg(feature = "mav2-message-signing")]
124 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
125}
126
127pub struct Connection<M: Message> {
129 inner: ConnectionInner,
130 _p: PhantomData<M>,
131}
132
133enum ConnectionInner {
134 #[cfg(feature = "transport-tcp")]
135 Tcp(TcpConnection),
136 #[cfg(feature = "transport-udp")]
137 Udp(UdpConnection),
138 #[cfg(feature = "transport-direct-serial")]
139 Serial(SerialConnection),
140 File(FileConnection),
141}
142
143impl<M: Message> Connection<M> {
144 fn new(inner: ConnectionInner) -> Self {
145 Self {
146 inner,
147 _p: PhantomData,
148 }
149 }
150}
151
152#[cfg(feature = "transport-tcp")]
153impl<M: Message> From<TcpConnection> for Connection<M> {
154 fn from(value: TcpConnection) -> Self {
155 Self::new(ConnectionInner::Tcp(value))
156 }
157}
158
159#[cfg(feature = "transport-udp")]
160impl<M: Message> From<UdpConnection> for Connection<M> {
161 fn from(value: UdpConnection) -> Self {
162 Self::new(ConnectionInner::Udp(value))
163 }
164}
165
166#[cfg(feature = "transport-direct-serial")]
167impl<M: Message> From<SerialConnection> for Connection<M> {
168 fn from(value: SerialConnection) -> Self {
169 Self::new(ConnectionInner::Serial(value))
170 }
171}
172
173impl<M: Message> From<FileConnection> for Connection<M> {
174 fn from(value: FileConnection) -> Self {
175 Self::new(ConnectionInner::File(value))
176 }
177}
178
179impl<M: Message> MavConnection<M> for Connection<M> {
180 fn recv(&self) -> Result<(MavHeader, M), MessageReadError> {
181 match &self.inner {
182 #[cfg(feature = "transport-tcp")]
183 ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv(conn),
184 #[cfg(feature = "transport-udp")]
185 ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv(conn),
186 #[cfg(feature = "transport-direct-serial")]
187 ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv(conn),
188 ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv(conn),
189 }
190 }
191
192 fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError> {
193 match &self.inner {
194 #[cfg(feature = "transport-tcp")]
195 ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv_raw(conn),
196 #[cfg(feature = "transport-udp")]
197 ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv_raw(conn),
198 #[cfg(feature = "transport-direct-serial")]
199 ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv_raw(conn),
200 ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv_raw(conn),
201 }
202 }
203
204 fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError> {
205 match &self.inner {
206 #[cfg(feature = "transport-tcp")]
207 ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::try_recv(conn),
208 #[cfg(feature = "transport-udp")]
209 ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::try_recv(conn),
210 #[cfg(feature = "transport-direct-serial")]
211 ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::try_recv(conn),
212 ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::try_recv(conn),
213 }
214 }
215
216 fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError> {
217 match &self.inner {
218 #[cfg(feature = "transport-tcp")]
219 ConnectionInner::Tcp(conn) => {
220 <TcpConnection as MavConnection<M>>::send(conn, header, data)
221 }
222 #[cfg(feature = "transport-udp")]
223 ConnectionInner::Udp(conn) => {
224 <UdpConnection as MavConnection<M>>::send(conn, header, data)
225 }
226 #[cfg(feature = "transport-direct-serial")]
227 ConnectionInner::Serial(conn) => {
228 <SerialConnection as MavConnection<M>>::send(conn, header, data)
229 }
230 ConnectionInner::File(conn) => {
231 <FileConnection as MavConnection<M>>::send(conn, header, data)
232 }
233 }
234 }
235
236 fn set_protocol_version(&mut self, version: MavlinkVersion) {
237 match &mut self.inner {
238 #[cfg(feature = "transport-tcp")]
239 ConnectionInner::Tcp(conn) => {
240 <TcpConnection as MavConnection<M>>::set_protocol_version(conn, version);
241 }
242 #[cfg(feature = "transport-udp")]
243 ConnectionInner::Udp(conn) => {
244 <UdpConnection as MavConnection<M>>::set_protocol_version(conn, version);
245 }
246 #[cfg(feature = "transport-direct-serial")]
247 ConnectionInner::Serial(conn) => {
248 <SerialConnection as MavConnection<M>>::set_protocol_version(conn, version);
249 }
250 ConnectionInner::File(conn) => {
251 <FileConnection as MavConnection<M>>::set_protocol_version(conn, version);
252 }
253 }
254 }
255
256 fn protocol_version(&self) -> MavlinkVersion {
257 match &self.inner {
258 #[cfg(feature = "transport-tcp")]
259 ConnectionInner::Tcp(conn) => {
260 <TcpConnection as MavConnection<M>>::protocol_version(conn)
261 }
262 #[cfg(feature = "transport-udp")]
263 ConnectionInner::Udp(conn) => {
264 <UdpConnection as MavConnection<M>>::protocol_version(conn)
265 }
266 #[cfg(feature = "transport-direct-serial")]
267 ConnectionInner::Serial(conn) => {
268 <SerialConnection as MavConnection<M>>::protocol_version(conn)
269 }
270 ConnectionInner::File(conn) => {
271 <FileConnection as MavConnection<M>>::protocol_version(conn)
272 }
273 }
274 }
275
276 fn set_allow_recv_any_version(&mut self, allow: bool) {
277 match &mut self.inner {
278 #[cfg(feature = "transport-tcp")]
279 ConnectionInner::Tcp(conn) => {
280 <TcpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
281 }
282 #[cfg(feature = "transport-udp")]
283 ConnectionInner::Udp(conn) => {
284 <UdpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
285 }
286 #[cfg(feature = "transport-direct-serial")]
287 ConnectionInner::Serial(conn) => {
288 <SerialConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
289 }
290 ConnectionInner::File(conn) => {
291 <FileConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
292 }
293 }
294 }
295
296 fn allow_recv_any_version(&self) -> bool {
297 match &self.inner {
298 #[cfg(feature = "transport-tcp")]
299 ConnectionInner::Tcp(conn) => {
300 <TcpConnection as MavConnection<M>>::allow_recv_any_version(conn)
301 }
302 #[cfg(feature = "transport-udp")]
303 ConnectionInner::Udp(conn) => {
304 <UdpConnection as MavConnection<M>>::allow_recv_any_version(conn)
305 }
306 #[cfg(feature = "transport-direct-serial")]
307 ConnectionInner::Serial(conn) => {
308 <SerialConnection as MavConnection<M>>::allow_recv_any_version(conn)
309 }
310 ConnectionInner::File(conn) => {
311 <FileConnection as MavConnection<M>>::allow_recv_any_version(conn)
312 }
313 }
314 }
315
316 #[cfg(feature = "mav2-message-signing")]
317 fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
318 let mut signing_data = signing_data;
319 match &mut self.inner {
320 #[cfg(feature = "transport-tcp")]
321 ConnectionInner::Tcp(conn) => {
322 <TcpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
323 }
324 #[cfg(feature = "transport-udp")]
325 ConnectionInner::Udp(conn) => {
326 <UdpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
327 }
328 #[cfg(feature = "transport-direct-serial")]
329 ConnectionInner::Serial(conn) => {
330 <SerialConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
331 }
332 ConnectionInner::File(conn) => {
333 <FileConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
334 }
335 }
336 }
337}
338
339pub fn connect<M: Message + Sync + Send>(address: &str) -> io::Result<Connection<M>> {
361 ConnectionAddress::parse_address(address)?.connect::<M>()
362}
363
364#[cfg(any(feature = "transport-tcp", feature = "transport-udp"))]
366pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
367 address: &T,
368) -> Result<std::net::SocketAddr, io::Error> {
369 address
370 .to_socket_addrs()?
371 .next()
372 .ok_or(io::Error::other("Host address lookup failed"))
373}
374
375pub trait Connectable: Display {
377 fn connect<M: Message>(&self) -> io::Result<Connection<M>>;
384}
385
386impl Connectable for ConnectionAddress {
387 fn connect<M>(&self) -> std::io::Result<Connection<M>>
388 where
389 M: Message,
390 {
391 match self {
392 #[cfg(feature = "transport-tcp")]
393 Self::Tcp(config) => config.connect::<M>(),
394 #[cfg(feature = "transport-udp")]
395 Self::Udp(config) => config.connect::<M>(),
396 #[cfg(feature = "transport-direct-serial")]
397 Self::Serial(config) => config.connect::<M>(),
398 Self::File(config) => config.connect::<M>(),
399 }
400 }
401}