1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
use crate::common::MavMessage;
use crate::{MavFrame, MavHeader, MavlinkVersion};
use std::io::{self};
#[cfg(feature = "tcp")]
mod tcp;
#[cfg(feature = "udp")]
mod udp;
#[cfg(feature = "direct-serial")]
mod direct_serial;
pub trait MavConnection {
fn recv(&self) -> io::Result<(MavHeader,MavMessage)>;
fn send(&self, header: &MavHeader, data: &MavMessage) -> io::Result<()>;
fn set_protocol_version(&mut self, version: MavlinkVersion);
fn get_protocol_version(&self) -> MavlinkVersion;
fn send_frame(&self, frame: &MavFrame) -> io::Result<()> {
self.send(&frame.header, &frame.msg)
}
fn recv_frame(&self) -> io::Result<MavFrame> {
let (header,msg) = self.recv()?;
let protocol_version = self.get_protocol_version();
Ok(MavFrame{header,msg,protocol_version})
}
fn send_default(&self, data: &MavMessage) -> io::Result<()> {
let header = MavHeader::get_default_header();
self.send(&header, data)
}
}
pub fn connect(address: &str) -> io::Result<Box<MavConnection + Sync + Send>> {
let protocol_err = Err(io::Error::new(
io::ErrorKind::AddrNotAvailable,
"Protocol unsupported",
));
if cfg!(feature = "tcp") && address.starts_with("tcp") {
#[cfg(feature = "tcp")] {
tcp::select_protocol(address)
}
#[cfg(not(feature = "tcp"))] {
protocol_err
}
} else if cfg!(feature = "udp") && address.starts_with("udp") {
#[cfg(feature = "udp")] {
udp::select_protocol(address)
}
#[cfg(not(feature = "udp"))] {
protocol_err
}
} else if cfg!(feature = "direct-serial") && address.starts_with("serial:") {
#[cfg(feature = "direct-serial")] {
Ok(Box::new(direct_serial::open(&address["serial:".len()..])?))
}
#[cfg(not(feature = "direct-serial"))] {
protocol_err
}
} else {
protocol_err
}
}