mavlink_core/connection/
mod.rs1use crate::{
2 connectable::ConnectionAddress, MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message,
3};
4
5use core::fmt::Display;
6use std::io::{self};
7
8#[cfg(feature = "tcp")]
9pub mod tcp;
10
11#[cfg(feature = "udp")]
12pub mod udp;
13
14#[cfg(feature = "direct-serial")]
15pub mod direct_serial;
16
17#[cfg(feature = "signing")]
18use crate::SigningConfig;
19
20pub mod file;
21
22pub trait MavConnection<M: Message> {
24 fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
28
29 fn recv_raw(&self) -> Result<MAVLinkMessageRaw, crate::error::MessageReadError>;
33
34 fn try_recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;
39
40 fn send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError>;
42
43 fn set_protocol_version(&mut self, version: MavlinkVersion);
45 fn protocol_version(&self) -> MavlinkVersion;
47
48 fn set_allow_recv_any_version(&mut self, allow: bool);
52 fn allow_recv_any_version(&self) -> bool;
54
55 fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, crate::error::MessageWriteError> {
57 self.send(&frame.header, &frame.msg)
58 }
59
60 fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
62 let (header, msg) = self.recv()?;
63 let protocol_version = self.protocol_version();
64 Ok(MavFrame {
65 header,
66 msg,
67 protocol_version,
68 })
69 }
70
71 fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
73 let header = MavHeader::default();
74 self.send(&header, data)
75 }
76
77 #[cfg(feature = "signing")]
79 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
80}
81
82pub fn connect<M: Message + Sync + Send>(
97 address: &str,
98) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
99 ConnectionAddress::parse_address(address)?.connect::<M>()
100}
101
102#[cfg(any(feature = "tcp", feature = "udp"))]
104pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
105 address: &T,
106) -> Result<std::net::SocketAddr, io::Error> {
107 address.to_socket_addrs()?.next().ok_or(io::Error::new(
108 io::ErrorKind::Other,
109 "Host address lookup failed",
110 ))
111}
112
113pub trait Connectable: Display {
115 fn connect<M: Message>(&self) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>>;
117}
118
119impl Connectable for ConnectionAddress {
120 fn connect<M>(&self) -> std::io::Result<Box<dyn crate::MavConnection<M> + Sync + Send>>
121 where
122 M: Message,
123 {
124 match self {
125 #[cfg(feature = "tcp")]
126 Self::Tcp(config) => config.connect::<M>(),
127 #[cfg(feature = "udp")]
128 Self::Udp(config) => config.connect::<M>(),
129 #[cfg(feature = "direct-serial")]
130 Self::Serial(config) => config.connect::<M>(),
131 Self::File(config) => config.connect::<M>(),
132 }
133 }
134}