mavlink_core/connection/
udp.rs

1//! UDP MAVLink connection
2
3use crate::connection::get_socket_addr;
4use crate::connection::MavConnection;
5use crate::peek_reader::PeekReader;
6#[cfg(not(feature = "signing"))]
7use crate::read_raw_versioned_msg;
8#[cfg(feature = "signing")]
9use crate::read_raw_versioned_msg_signed;
10use crate::Connectable;
11use crate::MAVLinkMessageRaw;
12use crate::{MavHeader, MavlinkVersion, Message, ReadVersion};
13use core::ops::DerefMut;
14use std::collections::VecDeque;
15use std::io::{self, Read};
16use std::net::{SocketAddr, UdpSocket};
17use std::sync::Mutex;
18
19#[cfg(not(feature = "signing"))]
20use crate::{read_versioned_msg, write_versioned_msg};
21
22#[cfg(feature = "signing")]
23use crate::{read_versioned_msg_signed, write_versioned_msg_signed, SigningConfig, SigningData};
24
25pub mod config;
26
27use config::{UdpConfig, UdpMode};
28
29struct UdpRead {
30    socket: UdpSocket,
31    buffer: VecDeque<u8>,
32    last_recv_address: Option<SocketAddr>,
33}
34
35const MTU_SIZE: usize = 1500;
36impl Read for UdpRead {
37    fn read(&mut self, buf: &mut [u8]) -> io::Result<usize> {
38        if !self.buffer.is_empty() {
39            self.buffer.read(buf)
40        } else {
41            let mut read_buffer = [0u8; MTU_SIZE];
42            let (n_buffer, address) = self.socket.recv_from(&mut read_buffer)?;
43            let n = (&read_buffer[0..n_buffer]).read(buf)?;
44            self.buffer.extend(&read_buffer[n..n_buffer]);
45
46            self.last_recv_address = Some(address);
47            Ok(n)
48        }
49    }
50}
51
52struct UdpWrite {
53    socket: UdpSocket,
54    dest: Option<SocketAddr>,
55    sequence: u8,
56}
57
58pub struct UdpConnection {
59    reader: Mutex<PeekReader<UdpRead>>,
60    writer: Mutex<UdpWrite>,
61    protocol_version: MavlinkVersion,
62    recv_any_version: bool,
63    server: bool,
64    #[cfg(feature = "signing")]
65    signing_data: Option<SigningData>,
66}
67
68impl UdpConnection {
69    fn new(socket: UdpSocket, server: bool, dest: Option<SocketAddr>) -> io::Result<Self> {
70        Ok(Self {
71            server,
72            reader: Mutex::new(PeekReader::new(UdpRead {
73                socket: socket.try_clone()?,
74                buffer: VecDeque::new(),
75                last_recv_address: None,
76            })),
77            writer: Mutex::new(UdpWrite {
78                socket,
79                dest,
80                sequence: 0,
81            }),
82            protocol_version: MavlinkVersion::V2,
83            recv_any_version: false,
84            #[cfg(feature = "signing")]
85            signing_data: None,
86        })
87    }
88}
89
90impl<M: Message> MavConnection<M> for UdpConnection {
91    fn recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> {
92        let mut reader = self.reader.lock().unwrap();
93
94        loop {
95            let version = ReadVersion::from_conn_cfg::<_, M>(self);
96            #[cfg(not(feature = "signing"))]
97            let result = read_versioned_msg(reader.deref_mut(), version);
98            #[cfg(feature = "signing")]
99            let result =
100                read_versioned_msg_signed(reader.deref_mut(), version, self.signing_data.as_ref());
101            if self.server {
102                if let addr @ Some(_) = reader.reader_ref().last_recv_address {
103                    self.writer.lock().unwrap().dest = addr;
104                }
105            }
106            if let ok @ Ok(..) = result {
107                return ok;
108            }
109        }
110    }
111
112    fn recv_raw(&self) -> Result<MAVLinkMessageRaw, crate::error::MessageReadError> {
113        let mut reader = self.reader.lock().unwrap();
114
115        loop {
116            let version = ReadVersion::from_conn_cfg::<_, M>(self);
117            #[cfg(not(feature = "signing"))]
118            let result = read_raw_versioned_msg::<M, _>(reader.deref_mut(), version);
119            #[cfg(feature = "signing")]
120            let result = read_raw_versioned_msg_signed::<M, _>(
121                reader.deref_mut(),
122                version,
123                self.signing_data.as_ref(),
124            );
125            if self.server {
126                if let addr @ Some(_) = reader.reader_ref().last_recv_address {
127                    self.writer.lock().unwrap().dest = addr;
128                }
129            }
130            if let ok @ Ok(..) = result {
131                return ok;
132            }
133        }
134    }
135
136    fn try_recv(&self) -> Result<(MavHeader, M), crate::error::MessageReadError> {
137        let mut reader = self.reader.lock().unwrap();
138        let version = ReadVersion::from_conn_cfg::<_, M>(self);
139
140        #[cfg(not(feature = "signing"))]
141        let result = read_versioned_msg(reader.deref_mut(), version);
142        #[cfg(feature = "signing")]
143        let result =
144            read_versioned_msg_signed(reader.deref_mut(), version, self.signing_data.as_ref());
145
146        if self.server {
147            if let addr @ Some(_) = reader.reader_ref().last_recv_address {
148                self.writer.lock().unwrap().dest = addr;
149            }
150        }
151
152        result
153    }
154
155    fn send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError> {
156        let mut guard = self.writer.lock().unwrap();
157        let state = &mut *guard;
158
159        let header = MavHeader {
160            sequence: state.sequence,
161            system_id: header.system_id,
162            component_id: header.component_id,
163        };
164
165        state.sequence = state.sequence.wrapping_add(1);
166
167        let len = if let Some(addr) = state.dest {
168            let mut buf = Vec::new();
169            #[cfg(not(feature = "signing"))]
170            write_versioned_msg(&mut buf, self.protocol_version, header, data)?;
171            #[cfg(feature = "signing")]
172            write_versioned_msg_signed(
173                &mut buf,
174                self.protocol_version,
175                header,
176                data,
177                self.signing_data.as_ref(),
178            )?;
179            state.socket.send_to(&buf, addr)?
180        } else {
181            0
182        };
183
184        Ok(len)
185    }
186
187    fn set_protocol_version(&mut self, version: MavlinkVersion) {
188        self.protocol_version = version;
189    }
190
191    fn protocol_version(&self) -> MavlinkVersion {
192        self.protocol_version
193    }
194
195    fn set_allow_recv_any_version(&mut self, allow: bool) {
196        self.recv_any_version = allow;
197    }
198
199    fn allow_recv_any_version(&self) -> bool {
200        self.recv_any_version
201    }
202
203    #[cfg(feature = "signing")]
204    fn setup_signing(&mut self, signing_data: Option<SigningConfig>) {
205        self.signing_data = signing_data.map(SigningData::from_config);
206    }
207}
208
209impl Connectable for UdpConfig {
210    fn connect<M: Message>(&self) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
211        let (addr, server, dest): (&str, _, _) = match self.mode {
212            UdpMode::Udpin => (&self.address, true, None),
213            _ => ("0.0.0.0:0", false, Some(get_socket_addr(&self.address)?)),
214        };
215        let socket = UdpSocket::bind(addr)?;
216        if matches!(self.mode, UdpMode::Udpcast) {
217            socket.set_broadcast(true)?;
218        }
219        Ok(Box::new(UdpConnection::new(socket, server, dest)?))
220    }
221}
222
223#[cfg(test)]
224mod tests {
225    use super::*;
226
227    #[test]
228    fn test_datagram_buffering() {
229        let receiver_socket = UdpSocket::bind("127.0.0.1:5000").unwrap();
230        let mut udp_reader = UdpRead {
231            socket: receiver_socket.try_clone().unwrap(),
232            buffer: VecDeque::new(),
233            last_recv_address: None,
234        };
235        let sender_socket = UdpSocket::bind("0.0.0.0:0").unwrap();
236        sender_socket.connect("127.0.0.1:5000").unwrap();
237
238        let datagram: Vec<u8> = (0..50).collect::<Vec<_>>();
239
240        let mut n_sent = sender_socket.send(&datagram).unwrap();
241        assert_eq!(n_sent, datagram.len());
242        n_sent = sender_socket.send(&datagram).unwrap();
243        assert_eq!(n_sent, datagram.len());
244
245        let mut buf = [0u8; 30];
246
247        let mut n_read = udp_reader.read(&mut buf).unwrap();
248        assert_eq!(n_read, 30);
249        assert_eq!(&buf[0..n_read], (0..30).collect::<Vec<_>>().as_slice());
250
251        n_read = udp_reader.read(&mut buf).unwrap();
252        assert_eq!(n_read, 20);
253        assert_eq!(&buf[0..n_read], (30..50).collect::<Vec<_>>().as_slice());
254
255        n_read = udp_reader.read(&mut buf).unwrap();
256        assert_eq!(n_read, 30);
257        assert_eq!(&buf[0..n_read], (0..30).collect::<Vec<_>>().as_slice());
258
259        n_read = udp_reader.read(&mut buf).unwrap();
260        assert_eq!(n_read, 20);
261        assert_eq!(&buf[0..n_read], (30..50).collect::<Vec<_>>().as_slice());
262    }
263}