Skip to content

Commit

Permalink
Minor refactoring
Browse files Browse the repository at this point in the history
  • Loading branch information
danieleades committed Aug 25, 2024
1 parent 2ab6785 commit 908e654
Show file tree
Hide file tree
Showing 9 changed files with 89 additions and 128 deletions.
7 changes: 3 additions & 4 deletions mavlink-bindgen/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ fn _generate(
) -> Result<GeneratedBindings, BindGenError> {
let mut bindings = vec![];

for entry_maybe in read_dir(&definitions_dir).map_err(|source| {
for entry_maybe in read_dir(definitions_dir).map_err(|source| {
BindGenError::CouldNotReadDefinitionsDirectory {
source,
path: definitions_dir.to_path_buf(),
Expand All @@ -55,8 +55,7 @@ fn _generate(
let definition_file = PathBuf::from(entry.file_name());
let module_name = util::to_module_name(&definition_file);

let mut definition_rs = PathBuf::from(&module_name);
definition_rs.set_extension("rs");
let definition_rs = PathBuf::from(&module_name).with_extension("rs");

let dest_path = destination_dir.join(definition_rs);
let mut outf = BufWriter::new(File::create(&dest_path).map_err(|source| {
Expand All @@ -67,7 +66,7 @@ fn _generate(
})?);

// generate code
parser::generate(&definitions_dir, &definition_file, &mut outf)?;
parser::generate(definitions_dir, &definition_file, &mut outf)?;

bindings.push(GeneratedBinding {
module_name,
Expand Down
12 changes: 3 additions & 9 deletions mavlink-bindgen/src/parser.rs
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ use std::fs::File;
use std::io::{BufReader, Write};
use std::path::{Path, PathBuf};
use std::str::FromStr;
use std::u32;

use quick_xml::{events::Event, Reader};

Expand Down Expand Up @@ -330,7 +329,7 @@ impl MavEnum {
value = quote!(#cnt);
} else {
let tmp_value = enum_entry.value.unwrap();
cnt = cnt.max(tmp_value as u32);
cnt = cnt.max(tmp_value);
let tmp = TokenStream::from_str(&tmp_value.to_string()).unwrap();
value = quote!(#tmp);
};
Expand Down Expand Up @@ -774,10 +773,11 @@ impl MavField {
}
}

#[derive(Debug, PartialEq, Clone)]
#[derive(Debug, PartialEq, Clone, Default)]
#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
pub enum MavType {
UInt8MavlinkVersion,
#[default]
UInt8,
UInt16,
UInt32,
Expand All @@ -792,12 +792,6 @@ pub enum MavType {
Array(Box<MavType>, usize),
}

impl Default for MavType {
fn default() -> Self {
Self::UInt8
}
}

impl MavType {
fn parse_type(s: &str) -> Option<Self> {
use self::MavType::*;
Expand Down
16 changes: 8 additions & 8 deletions mavlink-core/src/connection/direct_serial.rs
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
//! Serial MAVLINK connection

use crate::connection::MavConnection;
use crate::peek_reader::PeekReader;
use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message};
Expand All @@ -8,8 +10,6 @@ use std::sync::Mutex;
use crate::error::{MessageReadError, MessageWriteError};
use serial::{prelude::*, SystemPort};

/// Serial MAVLINK connection

pub fn open(settings: &str) -> io::Result<SerialConnection> {
let settings_toks: Vec<&str> = settings.split(':').collect();
if settings_toks.len() < 2 {
Expand All @@ -19,15 +19,15 @@ pub fn open(settings: &str) -> io::Result<SerialConnection> {
));
}

let baud_opt = settings_toks[1].parse::<usize>();
if baud_opt.is_err() {
let Ok(baud) = settings_toks[1]
.parse::<usize>()
.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,
Expand Down Expand Up @@ -91,7 +91,7 @@ impl<M: Message> MavConnection<M> for SerialConnection {
self.protocol_version = version;
}

fn get_protocol_version(&self) -> MavlinkVersion {
fn protocol_version(&self) -> MavlinkVersion {
self.protocol_version
}
}
6 changes: 3 additions & 3 deletions mavlink-core/src/connection/file.rs
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
//! File MAVLINK connection

use crate::connection::MavConnection;
use crate::error::{MessageReadError, MessageWriteError};
use crate::peek_reader::PeekReader;
Expand All @@ -7,8 +9,6 @@ use std::fs::File;
use std::io;
use std::sync::Mutex;

/// File MAVLINK connection

pub fn open(file_path: &str) -> io::Result<FileConnection> {
let file = File::open(file_path)?;

Expand Down Expand Up @@ -52,7 +52,7 @@ impl<M: Message> MavConnection<M> for FileConnection {
self.protocol_version = version;
}

fn get_protocol_version(&self) -> MavlinkVersion {
fn protocol_version(&self) -> MavlinkVersion {
self.protocol_version
}
}
18 changes: 6 additions & 12 deletions mavlink-core/src/connection/mod.rs
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ pub trait MavConnection<M: Message> {
fn send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError>;

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

/// Write whole frame
fn send_frame(&self, frame: &MavFrame<M>) -> Result<usize, crate::error::MessageWriteError> {
Expand All @@ -34,7 +34,7 @@ pub trait MavConnection<M: Message> {
/// Read whole frame
fn recv_frame(&self) -> Result<MavFrame<M>, crate::error::MessageReadError> {
let (header, msg) = self.recv()?;
let protocol_version = self.get_protocol_version();
let protocol_version = self.protocol_version();
Ok(MavFrame {
header,
msg,
Expand Down Expand Up @@ -107,14 +107,8 @@ pub fn connect<M: Message>(address: &str) -> io::Result<Box<dyn MavConnection<M>
pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
address: T,
) -> Result<std::net::SocketAddr, io::Error> {
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",
))
}
6 changes: 3 additions & 3 deletions mavlink-core/src/connection/tcp.rs
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
//! TCP MAVLink connection

use crate::connection::MavConnection;
use crate::peek_reader::PeekReader;
use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message};
Expand All @@ -10,8 +12,6 @@ use std::time::Duration;

use super::get_socket_addr;

/// TCP MAVLink connection

pub fn select_protocol<M: Message>(
address: &str,
) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
Expand Down Expand Up @@ -108,7 +108,7 @@ impl<M: Message> MavConnection<M> for TcpConnection {
self.protocol_version = version;
}

fn get_protocol_version(&self) -> MavlinkVersion {
fn protocol_version(&self) -> MavlinkVersion {
self.protocol_version
}
}
6 changes: 3 additions & 3 deletions mavlink-core/src/connection/udp.rs
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
//! UDP MAVLink connection

use std::collections::VecDeque;

use crate::connection::MavConnection;
Expand All @@ -11,8 +13,6 @@ use std::sync::Mutex;

use super::get_socket_addr;

/// UDP MAVLink connection

pub fn select_protocol<M: Message>(
address: &str,
) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
Expand Down Expand Up @@ -156,7 +156,7 @@ impl<M: Message> MavConnection<M> for UdpConnection {
self.protocol_version = version;
}

fn get_protocol_version(&self) -> MavlinkVersion {
fn protocol_version(&self) -> MavlinkVersion {
self.protocol_version
}
}
Expand Down
Loading

0 comments on commit 908e654

Please sign in to comment.