mavlink_core/connection/
mod.rs1use crate::{connectable::ConnectionAddress, MavFrame, MavHeader, MavlinkVersion, Message};
2
3use core::fmt::Display;
4use std::io::{self};
5
6#[cfg(feature = "tcp")]
7mod tcp;
8
9#[cfg(feature = "udp")]
10mod udp;
11
12#[cfg(feature = "direct-serial")]
13mod direct_serial;
14
15#[cfg(feature = "signing")]
16use crate::SigningConfig;
17
18mod file;
19
20pub trait MavConnection<M: Message> {
22 fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
26
27 fn try_recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
32
33 fn send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError>;
35
36 fn set_protocol_version(&mut self, version: MavlinkVersion);
38 fn protocol_version(&self) -> MavlinkVersion;
40
41 fn set_allow_recv_any_version(&mut self, allow: bool);
45 fn allow_recv_any_version(&self) -> bool;
47
48 fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, crate::error::MessageWriteError> {
50 self.send(&frame.header, &frame.msg)
51 }
52
53 fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
55 let (header, msg) = self.recv()?;
56 let protocol_version = self.protocol_version();
57 Ok(MavFrame {
58 header,
59 msg,
60 protocol_version,
61 })
62 }
63
64 fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
66 let header = MavHeader::default();
67 self.send(&header, data)
68 }
69
70 #[cfg(feature = "signing")]
72 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
73}
74
75pub fn connect<M: Message + Sync + Send>(
90 address: &str,
91) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
92 ConnectionAddress::parse_address(address)?.connect::<M>()
93}
94
95#[cfg(any(feature = "tcp", feature = "udp"))]
97pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
98 address: &T,
99) -> Result<std::net::SocketAddr, io::Error> {
100 address.to_socket_addrs()?.next().ok_or(io::Error::new(
101 io::ErrorKind::Other,
102 "Host address lookup failed",
103 ))
104}
105
106pub trait Connectable: Display {
108 fn connect<M: Message>(&self) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>>;
110}
111
112impl Connectable for ConnectionAddress {
113 fn connect<M>(&self) -> std::io::Result<Box<dyn crate::MavConnection<M> + Sync + Send>>
114 where
115 M: Message,
116 {
117 match self {
118 #[cfg(feature = "tcp")]
119 Self::Tcp(connectable) => connectable.connect::<M>(),
120 #[cfg(feature = "udp")]
121 Self::Udp(connectable) => connectable.connect::<M>(),
122 #[cfg(feature = "direct-serial")]
123 Self::Serial(connectable) => connectable.connect::<M>(),
124 Self::File(connectable) => connectable.connect::<M>(),
125 }
126 }
127}