mavlink_core/connection/
sync.rs1use core::fmt::Display;
2use core::marker::PhantomData;
3use std::io;
4
5#[cfg(feature = "transport-tcp")]
6use super::tcp::TcpConnection;
7
8#[cfg(feature = "transport-udp")]
9use super::udp::UdpConnection;
10
11#[cfg(feature = "transport-direct-serial")]
12use super::direct_serial::SerialConnection;
13
14use super::file::FileConnection;
15
16#[cfg(feature = "mav2-message-signing")]
17use crate::SigningConfig;
18
19use crate::error::MessageReadError;
20use crate::error::MessageWriteError;
21use crate::{
22 MAVLinkMessageRaw, MavFrame, MavHeader, MavlinkVersion, Message, connectable::ConnectionAddress,
23};
24
25pub trait MavConnection<M: Message> {
27 fn recv(&self) -> Result<(MavHeader, M), MessageReadError>;
36
37 fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError>;
46
47 fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError>;
56
57 fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError>;
63
64 fn set_protocol_version(&mut self, version: MavlinkVersion);
66 fn protocol_version(&self) -> MavlinkVersion;
68
69 fn set_allow_recv_any_version(&mut self, allow: bool);
73
74 fn allow_recv_any_version(&self) -> bool;
76
77 fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, MessageWriteError> {
83 self.send(&frame.header, &frame.msg)
84 }
85
86 fn recv_frame(&self) -> Result<MavFrame<M>, MessageReadError> {
92 let (header, msg) = self.recv()?;
93 let protocol_version = self.protocol_version();
94 Ok(MavFrame {
95 header,
96 msg,
97 protocol_version,
98 })
99 }
100
101 fn send_default(&self, data: &M) -> Result<usize, MessageWriteError> {
107 let header = MavHeader::default();
108 self.send(&header, data)
109 }
110
111 #[cfg(feature = "mav2-message-signing")]
113 fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
114}
115
116pub struct Connection<M: Message> {
118 inner: ConnectionInner,
119 _p: PhantomData<M>,
120}
121
122enum ConnectionInner {
123 #[cfg(feature = "transport-tcp")]
124 Tcp(TcpConnection),
125 #[cfg(feature = "transport-udp")]
126 Udp(UdpConnection),
127 #[cfg(feature = "transport-direct-serial")]
128 Serial(SerialConnection),
129 File(FileConnection),
130}
131
132impl<M: Message> Connection<M> {
133 fn new(inner: ConnectionInner) -> Self {
134 Self {
135 inner,
136 _p: PhantomData,
137 }
138 }
139}
140
141#[cfg(feature = "transport-tcp")]
142impl<M: Message> From<TcpConnection> for Connection<M> {
143 fn from(value: TcpConnection) -> Self {
144 Self::new(ConnectionInner::Tcp(value))
145 }
146}
147
148#[cfg(feature = "transport-udp")]
149impl<M: Message> From<UdpConnection> for Connection<M> {
150 fn from(value: UdpConnection) -> Self {
151 Self::new(ConnectionInner::Udp(value))
152 }
153}
154
155#[cfg(feature = "transport-direct-serial")]
156impl<M: Message> From<SerialConnection> for Connection<M> {
157 fn from(value: SerialConnection) -> Self {
158 Self::new(ConnectionInner::Serial(value))
159 }
160}
161
162impl<M: Message> From<FileConnection> for Connection<M> {
163 fn from(value: FileConnection) -> Self {
164 Self::new(ConnectionInner::File(value))
165 }
166}
167
168impl<M: Message> MavConnection<M> for Connection<M> {
169 fn recv(&self) -> Result<(MavHeader, M), MessageReadError> {
170 match &self.inner {
171 #[cfg(feature = "transport-tcp")]
172 ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv(conn),
173 #[cfg(feature = "transport-udp")]
174 ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv(conn),
175 #[cfg(feature = "transport-direct-serial")]
176 ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv(conn),
177 ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv(conn),
178 }
179 }
180
181 fn recv_raw(&self) -> Result<MAVLinkMessageRaw, MessageReadError> {
182 match &self.inner {
183 #[cfg(feature = "transport-tcp")]
184 ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::recv_raw(conn),
185 #[cfg(feature = "transport-udp")]
186 ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::recv_raw(conn),
187 #[cfg(feature = "transport-direct-serial")]
188 ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::recv_raw(conn),
189 ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::recv_raw(conn),
190 }
191 }
192
193 fn try_recv(&self) -> Result<(MavHeader, M), MessageReadError> {
194 match &self.inner {
195 #[cfg(feature = "transport-tcp")]
196 ConnectionInner::Tcp(conn) => <TcpConnection as MavConnection<M>>::try_recv(conn),
197 #[cfg(feature = "transport-udp")]
198 ConnectionInner::Udp(conn) => <UdpConnection as MavConnection<M>>::try_recv(conn),
199 #[cfg(feature = "transport-direct-serial")]
200 ConnectionInner::Serial(conn) => <SerialConnection as MavConnection<M>>::try_recv(conn),
201 ConnectionInner::File(conn) => <FileConnection as MavConnection<M>>::try_recv(conn),
202 }
203 }
204
205 fn send(&self, header: &MavHeader, data: &M) -> Result<usize, MessageWriteError> {
206 match &self.inner {
207 #[cfg(feature = "transport-tcp")]
208 ConnectionInner::Tcp(conn) => {
209 <TcpConnection as MavConnection<M>>::send(conn, header, data)
210 }
211 #[cfg(feature = "transport-udp")]
212 ConnectionInner::Udp(conn) => {
213 <UdpConnection as MavConnection<M>>::send(conn, header, data)
214 }
215 #[cfg(feature = "transport-direct-serial")]
216 ConnectionInner::Serial(conn) => {
217 <SerialConnection as MavConnection<M>>::send(conn, header, data)
218 }
219 ConnectionInner::File(conn) => {
220 <FileConnection as MavConnection<M>>::send(conn, header, data)
221 }
222 }
223 }
224
225 fn set_protocol_version(&mut self, version: MavlinkVersion) {
226 match &mut self.inner {
227 #[cfg(feature = "transport-tcp")]
228 ConnectionInner::Tcp(conn) => {
229 <TcpConnection as MavConnection<M>>::set_protocol_version(conn, version);
230 }
231 #[cfg(feature = "transport-udp")]
232 ConnectionInner::Udp(conn) => {
233 <UdpConnection as MavConnection<M>>::set_protocol_version(conn, version);
234 }
235 #[cfg(feature = "transport-direct-serial")]
236 ConnectionInner::Serial(conn) => {
237 <SerialConnection as MavConnection<M>>::set_protocol_version(conn, version);
238 }
239 ConnectionInner::File(conn) => {
240 <FileConnection as MavConnection<M>>::set_protocol_version(conn, version);
241 }
242 }
243 }
244
245 fn protocol_version(&self) -> MavlinkVersion {
246 match &self.inner {
247 #[cfg(feature = "transport-tcp")]
248 ConnectionInner::Tcp(conn) => {
249 <TcpConnection as MavConnection<M>>::protocol_version(conn)
250 }
251 #[cfg(feature = "transport-udp")]
252 ConnectionInner::Udp(conn) => {
253 <UdpConnection as MavConnection<M>>::protocol_version(conn)
254 }
255 #[cfg(feature = "transport-direct-serial")]
256 ConnectionInner::Serial(conn) => {
257 <SerialConnection as MavConnection<M>>::protocol_version(conn)
258 }
259 ConnectionInner::File(conn) => {
260 <FileConnection as MavConnection<M>>::protocol_version(conn)
261 }
262 }
263 }
264
265 fn set_allow_recv_any_version(&mut self, allow: bool) {
266 match &mut self.inner {
267 #[cfg(feature = "transport-tcp")]
268 ConnectionInner::Tcp(conn) => {
269 <TcpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
270 }
271 #[cfg(feature = "transport-udp")]
272 ConnectionInner::Udp(conn) => {
273 <UdpConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
274 }
275 #[cfg(feature = "transport-direct-serial")]
276 ConnectionInner::Serial(conn) => {
277 <SerialConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
278 }
279 ConnectionInner::File(conn) => {
280 <FileConnection as MavConnection<M>>::set_allow_recv_any_version(conn, allow);
281 }
282 }
283 }
284
285 fn allow_recv_any_version(&self) -> bool {
286 match &self.inner {
287 #[cfg(feature = "transport-tcp")]
288 ConnectionInner::Tcp(conn) => {
289 <TcpConnection as MavConnection<M>>::allow_recv_any_version(conn)
290 }
291 #[cfg(feature = "transport-udp")]
292 ConnectionInner::Udp(conn) => {
293 <UdpConnection as MavConnection<M>>::allow_recv_any_version(conn)
294 }
295 #[cfg(feature = "transport-direct-serial")]
296 ConnectionInner::Serial(conn) => {
297 <SerialConnection as MavConnection<M>>::allow_recv_any_version(conn)
298 }
299 ConnectionInner::File(conn) => {
300 <FileConnection as MavConnection<M>>::allow_recv_any_version(conn)
301 }
302 }
303 }
304
305 #[cfg(feature = "mav2-message-signing")]
306 fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
307 let mut signing_data = signing_data;
308 match &mut self.inner {
309 #[cfg(feature = "transport-tcp")]
310 ConnectionInner::Tcp(conn) => {
311 <TcpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
312 }
313 #[cfg(feature = "transport-udp")]
314 ConnectionInner::Udp(conn) => {
315 <UdpConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
316 }
317 #[cfg(feature = "transport-direct-serial")]
318 ConnectionInner::Serial(conn) => {
319 <SerialConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
320 }
321 ConnectionInner::File(conn) => {
322 <FileConnection as MavConnection<M>>::setup_signing(conn, signing_data.take());
323 }
324 }
325 }
326}
327
328pub fn connect<M: Message + Sync + Send>(address: &str) -> io::Result<Connection<M>> {
350 ConnectionAddress::parse_address(address)?.connect::<M>()
351}
352
353pub trait Connectable: Display {
355 fn connect<M: Message>(&self) -> io::Result<Connection<M>>;
362}
363
364impl Connectable for ConnectionAddress {
365 fn connect<M>(&self) -> std::io::Result<Connection<M>>
366 where
367 M: Message,
368 {
369 match self {
370 #[cfg(feature = "transport-tcp")]
371 Self::Tcp(config) => config.connect::<M>(),
372 #[cfg(feature = "transport-udp")]
373 Self::Udp(config) => config.connect::<M>(),
374 #[cfg(feature = "transport-direct-serial")]
375 Self::Serial(config) => config.connect::<M>(),
376 Self::File(config) => config.connect::<M>(),
377 }
378 }
379}