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
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
use crate::{MavFrame, MavHeader, MavlinkVersion, Message};

use std::io::{self};

#[cfg(feature = "tcp")]
mod tcp;

#[cfg(feature = "udp")]
mod udp;

#[cfg(feature = "direct-serial")]
mod direct_serial;

#[cfg(feature = "signing")]
use crate::SigningConfig;

mod file;

/// A MAVLink connection
pub trait MavConnection<M: Message> {
    /// Receive a mavlink message.
    ///
    /// Blocks until a valid frame is received, ignoring invalid messages.
    fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError>;

    /// Send a mavlink message
    fn send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError>;

    fn set_protocol_version(&mut self, version: MavlinkVersion);
    fn protocol_version(&self) -> MavlinkVersion;

    /// Write whole frame
    fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, crate::error::MessageWriteError> {
        self.send(&frame.header, &frame.msg)
    }

    /// Read whole frame
    fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
        let (header, msg) = self.recv()?;
        let protocol_version = self.protocol_version();
        Ok(MavFrame {
            header,
            msg,
            protocol_version,
        })
    }

    /// Send a message with default header
    fn send_default(&self, data: &M) -> Result<usize, crate::error::MessageWriteError> {
        let header = MavHeader::default();
        self.send(&header, data)
    }

    /// Setup secret key used for message signing, or disable message signing
    #[cfg(feature = "signing")]
    fn setup_signing(&mut self, signing_data: Option<SigningConfig>);
}

/// Connect to a MAVLink node by address string.
///
/// The address must be in one of the following formats:
///
///  * `tcpin:<addr>:<port>` to create a TCP server, listening for incoming connections
///  * `tcpout:<addr>:<port>` to create a TCP client
///  * `udpin:<addr>:<port>` to create a UDP server, listening for incoming packets
///  * `udpout:<addr>:<port>` to create a UDP client
///  * `udpbcast:<addr>:<port>` to create a UDP broadcast
///  * `serial:<port>:<baudrate>` to create a serial connection
///  * `file:<path>` to extract file data
///
/// The type of the connection is determined at runtime based on the address type, so the
/// connection is returned as a trait object.
pub fn connect<M: Message>(address: &str) -> io::Result<Box<dyn MavConnection<M> + 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 if address.starts_with("file") {
        Ok(Box::new(file::open(&address["file:".len()..])?))
    } else {
        protocol_err
    }
}

/// Returns the socket address for the given address.
pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
    address: T,
) -> Result<std::net::SocketAddr, io::Error> {
    address.to_socket_addrs()?.next().ok_or(io::Error::new(
        io::ErrorKind::Other,
        "Host address lookup failed",
    ))
}