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 send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError>;
29
30 fn set_protocol_version(&mut self, version: MavlinkVersion);
32 fn protocol_version(&self) -> MavlinkVersion;
34
35 fn set_allow_recv_any_version(&mut self, allow: bool);
39 fn allow_recv_any_version(&self) -> bool;
41
42 fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, crate::error::MessageWriteError> {
44 self.send(&frame.header, &frame.msg)
45 }
46
47 fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
49 let (header, msg) = self.recv()?;
50 let protocol_version = self.protocol_version();
51 Ok(MavFrame {
52 header,
53 msg,
54 protocol_version,
55 })
56 }
57
58 fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
60 let header = MavHeader::default();
61 self.send(&header, data)
62 }
63
64 #[cfg(feature = "signing")]
66 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
67}
68
69pub fn connect<M: Message + Sync + Send>(
84 address: &str,
85) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
86 ConnectionAddress::parse_address(address)?.connect::<M>()
87}
88
89#[cfg(any(feature = "tcp", feature = "udp"))]
91pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
92 address: &T,
93) -> Result<std::net::SocketAddr, io::Error> {
94 address.to_socket_addrs()?.next().ok_or(io::Error::new(
95 io::ErrorKind::Other,
96 "Host address lookup failed",
97 ))
98}
99
100pub trait Connectable: Display {
102 fn connect<M: Message>(&self) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>>;
104}
105
106impl Connectable for ConnectionAddress {
107 fn connect<M>(&self) -> std::io::Result<Box<dyn crate::MavConnection<M> + Sync + Send>>
108 where
109 M: Message,
110 {
111 match self {
112 #[cfg(feature = "tcp")]
113 Self::Tcp(connectable) => connectable.connect::<M>(),
114 #[cfg(feature = "udp")]
115 Self::Udp(connectable) => connectable.connect::<M>(),
116 #[cfg(feature = "direct-serial")]
117 Self::Serial(connectable) => connectable.connect::<M>(),
118 Self::File(connectable) => connectable.connect::<M>(),
119 }
120 }
121}