From eee501fb55cd546f4955e608959f5062fcd37b6d Mon Sep 17 00:00:00 2001 From: Daniel Eades Date: Mon, 20 Mar 2023 06:36:54 +0000 Subject: [PATCH] more refactoring --- build/parser.rs | 92 +++++++++++++++----------------------- src/bin/mavlink-dump.rs | 2 +- src/embedded.rs | 8 ++-- tests/process_log_files.rs | 2 +- 4 files changed, 43 insertions(+), 61 deletions(-) diff --git a/build/parser.rs b/build/parser.rs index 94415d60a9..6ee033cae7 100644 --- a/build/parser.rs +++ b/build/parser.rs @@ -57,17 +57,14 @@ impl MavProfile { fn update_enums(mut self) -> Self { for msg in self.messages.values() { for field in &msg.fields { - if let Some(ref enum_name) = field.enumtype { - // it is an enum - if let Some(ref dsp) = field.display { - // it is a bitmask - if dsp == "bitmask" { - // find the corresponding enum - for mut enm in self.enums.values_mut() { - if enm.name == *enum_name { - // this is the right enum - enm.bitfield = Some(field.mavtype.rust_type()); - } + if let Some(enum_name) = &field.enumtype { + // it is a bitmask + if let Some("bitmask") = field.display.as_deref() { + // find the corresponding enum + for mut enm in self.enums.values_mut() { + if enm.name == *enum_name { + // this is the right enum + enm.bitfield = Some(field.mavtype.rust_type()); } } } @@ -88,7 +85,7 @@ impl MavProfile { // } /// Simple header comment - fn emit_comments(&self) -> TokenStream { + fn emit_comments() -> TokenStream { quote!(#![doc = "This file was automatically generated, do not edit"]) } @@ -147,7 +144,7 @@ impl MavProfile { //TODO verify that id_width of u8 is OK even in mavlink v1 let id_width = format_ident!("u32"); - let comment = self.emit_comments(); + let comment = Self::emit_comments(); let msgs = self.emit_msgs(); let enum_names = self.emit_enum_names(); let struct_names = self.emit_struct_names(); @@ -155,15 +152,15 @@ impl MavProfile { let msg_ids = self.emit_msg_ids(); let msg_crc = self.emit_msg_crc(); - let mav_message = self.emit_mav_message(&enum_names, &struct_names); - let mav_message_parse = self.emit_mav_message_parse(&enum_names, &struct_names, &msg_ids); - let mav_message_crc = self.emit_mav_message_crc(&id_width, &msg_ids, &msg_crc); - let mav_message_name = self.emit_mav_message_name(&enum_names); - let mav_message_id = self.emit_mav_message_id(&enum_names, &msg_ids); - let mav_message_id_from_name = self.emit_mav_message_id_from_name(&enum_names, &msg_ids); + let mav_message = Self::emit_mav_message(&enum_names, &struct_names); + let mav_message_parse = Self::emit_mav_message_parse(&enum_names, &struct_names, &msg_ids); + let mav_message_crc = Self::emit_mav_message_crc(&id_width, &msg_ids, &msg_crc); + let mav_message_name = Self::emit_mav_message_name(&enum_names); + let mav_message_id = Self::emit_mav_message_id(&enum_names, &msg_ids); + let mav_message_id_from_name = Self::emit_mav_message_id_from_name(&enum_names, &msg_ids); let mav_message_default_from_id = - self.emit_mav_message_default_from_id(&enum_names, &msg_ids); - let mav_message_serialize = self.emit_mav_message_serialize(&enum_names); + Self::emit_mav_message_default_from_id(&enum_names, &msg_ids); + let mav_message_serialize = Self::emit_mav_message_serialize(&enum_names); quote! { #comment @@ -205,11 +202,7 @@ impl MavProfile { } } - fn emit_mav_message( - &self, - enums: &Vec, - structs: &Vec, - ) -> TokenStream { + fn emit_mav_message(enums: &[TokenStream], structs: &[TokenStream]) -> TokenStream { quote! { #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))] #[cfg_attr(feature = "serde", serde(tag = "type"))] @@ -220,7 +213,6 @@ impl MavProfile { } fn emit_mav_message_parse( - &self, enums: &[TokenStream], structs: &[TokenStream], ids: &[TokenStream], @@ -240,7 +232,6 @@ impl MavProfile { } fn emit_mav_message_crc( - &self, id_width: &Ident, ids: &[TokenStream], crc: &[TokenStream], @@ -257,7 +248,7 @@ impl MavProfile { } } - fn emit_mav_message_name(&self, enums: &Vec) -> TokenStream { + fn emit_mav_message_name(enums: &[TokenStream]) -> TokenStream { let enum_names = enums.iter().map(|enum_name| { let name = enum_name.to_string(); quote!(#name) @@ -272,7 +263,7 @@ impl MavProfile { } } - fn emit_mav_message_id(&self, enums: &Vec, ids: &Vec) -> TokenStream { + fn emit_mav_message_id(enums: &[TokenStream], ids: &[TokenStream]) -> TokenStream { let id_width = format_ident!("u32"); quote! { fn message_id(&self) -> #id_width { @@ -283,11 +274,7 @@ impl MavProfile { } } - fn emit_mav_message_id_from_name( - &self, - enums: &[TokenStream], - ids: &[TokenStream], - ) -> TokenStream { + fn emit_mav_message_id_from_name(enums: &[TokenStream], ids: &[TokenStream]) -> TokenStream { let enum_names = enums.iter().map(|enum_name| { let name = enum_name.to_string(); quote!(#name) @@ -305,11 +292,7 @@ impl MavProfile { } } - fn emit_mav_message_default_from_id( - &self, - enums: &[TokenStream], - ids: &[TokenStream], - ) -> TokenStream { + fn emit_mav_message_default_from_id(enums: &[TokenStream], ids: &[TokenStream]) -> TokenStream { let data_name = enums.iter().map(|enum_name| { let name = format_ident!("{}_DATA", enum_name.to_string()); quote!(#name) @@ -327,7 +310,7 @@ impl MavProfile { } } - fn emit_mav_message_serialize(&self, enums: &Vec) -> TokenStream { + fn emit_mav_message_serialize(enums: &[TokenStream]) -> TokenStream { quote! { fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { match self { @@ -372,7 +355,7 @@ impl MavEnum { let value; #[cfg(feature = "emit-description")] - let description = if let Some(description) = enum_entry.description.as_ref() { + let description = if let Some(description) = &enum_entry.description { quote!(#[doc = #description]) } else { quote!() @@ -416,9 +399,8 @@ impl MavEnum { let enum_name = self.emit_name(); #[cfg(feature = "emit-description")] - let description = if let Some(description) = self.description.as_ref() { - let desc = format!("{description}"); - quote!(#[doc = #desc]) + let description = if let Some(description) = &self.description { + quote!(#[doc = #description]) } else { quote!() }; @@ -518,7 +500,7 @@ impl MavMessage { #nametype } }) - .collect::>(); + .collect(); (field_toks, encoded_payload_len) } @@ -642,7 +624,7 @@ impl MavField { if matches!(self.mavtype, MavType::Array(_, _)) { let rt = TokenStream::from_str(&self.mavtype.rust_type()).unwrap(); mavtype = quote!(#rt); - } else if let Some(ref enumname) = self.enumtype { + } else if let Some(enumname) = &self.enumtype { let en = TokenStream::from_str(enumname).unwrap(); mavtype = quote!(#en); } else { @@ -1090,7 +1072,7 @@ pub fn parse_profile( let attr = attr.unwrap(); match stack.last() { Some(&MavXmlElement::Enum) => { - if let b"name" = attr.key.into_inner() { + if attr.key.into_inner() == b"name" { mavenum.name = attr .value .clone() @@ -1191,7 +1173,7 @@ pub fn parse_profile( if entry.params.is_none() { entry.params = Some(vec![]); } - if let b"index" = attr.key.into_inner() { + if attr.key.into_inner() == b"index" { let s = std::str::from_utf8(&attr.value).unwrap(); paramid = Some(s.parse::().unwrap()); } @@ -1241,7 +1223,7 @@ pub fn parse_profile( entry.description = Some(s.replace('\n', " ")); } (Some(&Param), Some(&Entry)) => { - if let Some(ref mut params) = entry.params { + if let Some(params) = &mut entry.params { // Some messages can jump between values, like: // 0, 1, 2, 7 if params.len() < paramid.unwrap() { @@ -1350,7 +1332,7 @@ pub fn extra_crc(msg: &MavMessage) -> u8 { let mut crc = CRCu16::crc16mcrf4cc(); crc.digest(msg.name.as_bytes()); - crc.digest(" ".as_bytes()); + crc.digest(b" "); let mut f = msg.fields.clone(); // only mavlink 1 fields should be part of the extra_crc @@ -1358,13 +1340,13 @@ pub fn extra_crc(msg: &MavMessage) -> u8 { f.sort_by(|a, b| a.mavtype.compare(&b.mavtype)); for field in &f { crc.digest(field.mavtype.primitive_type().as_bytes()); - crc.digest(" ".as_bytes()); + crc.digest(b" "); if field.name == "mavtype" { - crc.digest("type".as_bytes()); + crc.digest(b"type"); } else { crc.digest(field.name.as_bytes()); } - crc.digest(" ".as_bytes()); + crc.digest(b" "); if let MavType::Array(_, size) = field.mavtype { crc.digest(&[size as u8]); } @@ -1435,7 +1417,7 @@ impl MavXmlFilter { Some(kind) => kind, }; - if let MavXmlElement::Message = id { + if id == MavXmlElement::Message { self.extension_filter.is_in = false; } } diff --git a/src/bin/mavlink-dump.rs b/src/bin/mavlink-dump.rs index 2f262af9f9..9d30e84d40 100644 --- a/src/bin/mavlink-dump.rs +++ b/src/bin/mavlink-dump.rs @@ -49,7 +49,7 @@ fn main() { println!("received: {msg:?}"); } Err(MessageReadError::Io(e)) => { - if let std::io::ErrorKind::WouldBlock = e.kind() { + if e.kind() == std::io::ErrorKind::WouldBlock { //no messages currently available to receive -- wait a while thread::sleep(Duration::from_secs(1)); continue; diff --git a/src/embedded.rs b/src/embedded.rs index 64138a5b14..574ae2b826 100644 --- a/src/embedded.rs +++ b/src/embedded.rs @@ -5,8 +5,8 @@ pub trait Read { fn read_u8(&mut self) -> Result; fn read_exact(&mut self, buf: &mut [u8]) -> Result<(), MessageReadError> { - for i in 0..buf.len() { - buf[i] = self.read_u8()?; + for byte in buf { + *byte = self.read_u8()?; } Ok(()) @@ -26,8 +26,8 @@ pub trait Write { impl> Write for W { fn write_all(&mut self, buf: &[u8]) -> Result<(), MessageWriteError> { - for i in 0..buf.len() { - nb::block!(self.write(buf[i])).map_err(|_| MessageWriteError::Io)?; + for byte in buf { + nb::block!(self.write(*byte)).map_err(|_| MessageWriteError::Io)?; } Ok(()) diff --git a/tests/process_log_files.rs b/tests/process_log_files.rs index a38665fd8f..0bf71544f8 100644 --- a/tests/process_log_files.rs +++ b/tests/process_log_files.rs @@ -36,7 +36,7 @@ mod process_files { counter += 1; } Err(MessageReadError::Io(e)) => { - if let std::io::ErrorKind::WouldBlock = e.kind() { + if e.kind() == std::io::ErrorKind::WouldBlock { continue; } else { println!("recv error: {e:?}");