diff --git a/mavlink-core/src/connection/direct_serial.rs b/mavlink-core/src/connection/direct_serial.rs index 644839416b..63262e35f6 100644 --- a/mavlink-core/src/connection/direct_serial.rs +++ b/mavlink-core/src/connection/direct_serial.rs @@ -19,15 +19,15 @@ pub fn open(settings: &str) -> io::Result { )); } - let baud_opt = settings_toks[1].parse::(); - if baud_opt.is_err() { + let Ok(baud) = settings_toks[1] + .parse::() + .map(serial::core::BaudRate::from_speed) + else { return Err(io::Error::new( io::ErrorKind::AddrNotAvailable, "Invalid baud rate", )); - } - - let baud = serial::core::BaudRate::from_speed(baud_opt.unwrap()); + }; let settings = serial::core::PortSettings { baud_rate: baud, diff --git a/mavlink-core/src/connection/mod.rs b/mavlink-core/src/connection/mod.rs index 9fe6908aa2..035f63eb28 100644 --- a/mavlink-core/src/connection/mod.rs +++ b/mavlink-core/src/connection/mod.rs @@ -107,14 +107,8 @@ pub fn connect(address: &str) -> io::Result pub(crate) fn get_socket_addr( address: T, ) -> Result { - let addr = match address.to_socket_addrs()?.next() { - Some(addr) => addr, - None => { - return Err(io::Error::new( - io::ErrorKind::Other, - "Host address lookup failed", - )); - } - }; - Ok(addr) + address.to_socket_addrs()?.next().ok_or(io::Error::new( + io::ErrorKind::Other, + "Host address lookup failed", + )) } diff --git a/mavlink-core/src/connection/udp.rs b/mavlink-core/src/connection/udp.rs index c8a3d764c6..17926aea02 100644 --- a/mavlink-core/src/connection/udp.rs +++ b/mavlink-core/src/connection/udp.rs @@ -1,3 +1,5 @@ +//! UDP MAVLink connection +//! use std::collections::VecDeque; use crate::connection::MavConnection; @@ -11,8 +13,6 @@ use std::sync::Mutex; use super::get_socket_addr; -/// UDP MAVLink connection - pub fn select_protocol( address: &str, ) -> io::Result + Sync + Send>> {