From 67acdf45ce09d9de628e39b3bf363cf4c67a5850 Mon Sep 17 00:00:00 2001 From: Daniel Eades Date: Mon, 20 Mar 2023 06:36:54 +0000 Subject: [PATCH] update linting, address lints --- .github/workflows/test.yml | 7 ++- build/binder.rs | 1 + build/parser.rs | 87 +++++++++++++++++--------------------- src/bin/mavlink-dump.rs | 2 +- src/connection/udp.rs | 3 +- src/embedded.rs | 8 ++-- src/lib.rs | 14 +++--- src/utils.rs | 2 +- tests/process_log_files.rs | 2 +- 9 files changed, 58 insertions(+), 68 deletions(-) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index dce4f54c07..b439439622 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -19,12 +19,11 @@ jobs: - uses: actions/checkout@master - uses: dtolnay/rust-toolchain@master with: - toolchain: nightly-2022-11-30 + toolchain: nightly-2023-10-21 components: clippy - - uses: actions-rs/clippy-check@v1 + - uses: actions-rs-plus/clippy-check@v2 with: - token: ${{ secrets.GITHUB_TOKEN }} - args: --all --all-targets + args: --all --all-targets --features format-generated-code internal-tests: runs-on: ubuntu-latest diff --git a/build/binder.rs b/build/binder.rs index be68f7a9c3..099ef24e9b 100644 --- a/build/binder.rs +++ b/build/binder.rs @@ -11,6 +11,7 @@ pub fn generate(modules: Vec, out: &mut W) { #[allow(clippy::field_reassign_with_default)] #[allow(non_snake_case)] #[allow(clippy::unnecessary_cast)] + #[allow(clippy::bad_bit_mask)] #[cfg(feature = #module)] pub mod #module_ident; } diff --git a/build/parser.rs b/build/parser.rs index e797e3882f..20a883a2eb 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 enm in self.enums.values_mut() { - if enm.name == *enum_name { - // this is the right enum - enm.bitfield = Some(field.mavtype.rust_primitive_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 enm in self.enums.values_mut() { + if enm.name == *enum_name { + // this is the right enum + enm.bitfield = Some(field.mavtype.rust_primitive_type()); } } } @@ -503,13 +500,13 @@ impl MavMessage { fn emit_serialize_vars(&self) -> TokenStream { let ser_vars = self.fields.iter().map(|f| f.rust_writer()); quote! { - let mut _tmp = BytesMut::new(bytes); + let mut __tmp = BytesMut::new(bytes); #(#ser_vars)* if matches!(version, MavlinkVersion::V2) { - let len = _tmp.len(); - crate::remove_trailing_zeroes(&mut bytes[..len]) + let len = __tmp.len(); + crate::remove_trailing_zeroes(&bytes[..len]) } else { - _tmp.len() + __tmp.len() } } } @@ -528,21 +525,21 @@ impl MavMessage { } } else { quote! { - let avail_len = _input.len(); + let avail_len = __input.len(); let mut payload_buf = [0; Self::ENCODED_LEN]; let mut buf = if avail_len < Self::ENCODED_LEN { //copy available bytes into an oversized buffer filled with zeros - payload_buf[0..avail_len].copy_from_slice(_input); + payload_buf[0..avail_len].copy_from_slice(__input); Bytes::new(&payload_buf) } else { // fast zero copy - Bytes::new(_input) + Bytes::new(__input) }; - let mut _struct = Self::default(); + let mut __struct = Self::default(); #(#deser_vars)* - Ok(_struct) + Ok(__struct) } } } @@ -607,7 +604,7 @@ impl MavMessage { const EXTRA_CRC: u8 = #extra_crc; const ENCODED_LEN: usize = #msg_encoded_len; - fn deser(_version: MavlinkVersion, _input: &[u8]) -> Result { + fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result { #deser_vars } @@ -643,7 +640,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 { @@ -695,7 +692,7 @@ impl MavField { } let ts = TokenStream::from_str(&name).unwrap(); let name = quote!(#ts); - let buf = format_ident!("_tmp"); + let buf = format_ident!("__tmp"); self.mavtype.rust_writer(&name, buf) } @@ -703,7 +700,7 @@ impl MavField { fn rust_reader(&self) -> TokenStream { let _name = TokenStream::from_str(&self.name).unwrap(); - let name = quote!(_struct.#_name); + let name = quote!(__struct.#_name); let buf = format_ident!("buf"); if let Some(enum_name) = &self.enumtype { // TODO: handle enum arrays properly, rather than just generating @@ -1122,7 +1119,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() @@ -1273,7 +1270,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() { @@ -1382,7 +1379,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 @@ -1390,13 +1387,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]); } @@ -1443,31 +1440,25 @@ impl MavXmlFilter { Ok(content) => { match content { Event::Start(bytes) | Event::Empty(bytes) => { - let id = match identify_element(bytes.name().into_inner()) { - None => { - panic!( - "unexpected element {:?}", - String::from_utf8_lossy(bytes.name().into_inner()) - ); - } - Some(kind) => kind, + let Some(id) = identify_element(bytes.name().into_inner()) else { + panic!( + "unexpected element {:?}", + String::from_utf8_lossy(bytes.name().into_inner()) + ); }; - if let MavXmlElement::Extensions = id { + if id == MavXmlElement::Extensions { self.extension_filter.is_in = true; } } Event::End(bytes) => { - let id = match identify_element(bytes.name().into_inner()) { - None => { - panic!( - "unexpected element {:?}", - String::from_utf8_lossy(bytes.name().into_inner()) - ); - } - Some(kind) => kind, + let Some(id) = identify_element(bytes.name().into_inner()) else { + panic!( + "unexpected element {:?}", + String::from_utf8_lossy(bytes.name().into_inner()) + ); }; - 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/connection/udp.rs b/src/connection/udp.rs index 3bcd05a6f2..7357ca99c3 100644 --- a/src/connection/udp.rs +++ b/src/connection/udp.rs @@ -74,8 +74,7 @@ struct PacketBuf { impl PacketBuf { pub fn new() -> Self { - let mut v = Vec::new(); - v.resize(65536, 0); + let v = vec![0; 65536]; Self { buf: v, start: 0, 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/src/lib.rs b/src/lib.rs index 248ea9c1e4..8acb6dce89 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -191,7 +191,7 @@ impl MavFrame { let msg_id = match version { MavlinkVersion::V2 => buf.get_u24_le(), - MavlinkVersion::V1 => buf.get_u8() as u32, + MavlinkVersion::V1 => buf.get_u8().into(), }; match M::parse(version, msg_id, buf.remaining_bytes()) { @@ -498,10 +498,10 @@ impl MAVLinkV2MessageRaw { let payload_length: usize = self.payload_length().into(); // Signature to ensure the link is tamper-proof. - let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) != 0 { - Self::SIGNATURE_SIZE - } else { + let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 { 0 + } else { + Self::SIGNATURE_SIZE }; &mut self.0 @@ -521,10 +521,10 @@ impl MAVLinkV2MessageRaw { pub fn raw_bytes(&self) -> &[u8] { let payload_length = self.payload_length() as usize; - let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) != 0 { - Self::SIGNATURE_SIZE - } else { + let signature_size = if (self.incompatibility_flags() & MAVLINK_IFLAG_SIGNED) == 0 { 0 + } else { + Self::SIGNATURE_SIZE }; &self.0[..(1 + Self::HEADER_SIZE + payload_length + signature_size + 2)] diff --git a/src/utils.rs b/src/utils.rs index 58adfc6729..486c2ea0bb 100644 --- a/src/utils.rs +++ b/src/utils.rs @@ -4,7 +4,7 @@ /// /// There must always be at least one remaining byte even if it is a /// zero byte. -pub(crate) fn remove_trailing_zeroes(data: &mut [u8]) -> usize { +pub(crate) fn remove_trailing_zeroes(data: &[u8]) -> usize { let mut len = data.len(); for b in data[1..].iter().rev() { 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:?}");