diff --git a/Cargo.toml b/Cargo.toml index 65e9ef8b1d..b1a571a6b7 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -8,3 +8,8 @@ num-traits = { version = "0.2", default-features = false } num-derive = "0.3.2" bitflags = "1.2.1" byteorder = { version = "1.3.4", default-features = false } + +[workspace.lints.clippy] +all = "deny" +pedantic = "warn" +nursery = "warn" diff --git a/mavlink-bindgen/src/lib.rs b/mavlink-bindgen/src/lib.rs index 22f1efa2ce..23aae4b1d0 100644 --- a/mavlink-bindgen/src/lib.rs +++ b/mavlink-bindgen/src/lib.rs @@ -39,7 +39,7 @@ fn _generate( ) -> Result { 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(), @@ -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| { @@ -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, diff --git a/mavlink-bindgen/src/parser.rs b/mavlink-bindgen/src/parser.rs index e6ee66f3ab..e717ef88b5 100644 --- a/mavlink-bindgen/src/parser.rs +++ b/mavlink-bindgen/src/parser.rs @@ -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}; @@ -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); }; @@ -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, @@ -792,12 +792,6 @@ pub enum MavType { Array(Box, usize), } -impl Default for MavType { - fn default() -> Self { - Self::UInt8 - } -} - impl MavType { fn parse_type(s: &str) -> Option { use self::MavType::*; diff --git a/mavlink-core/src/connection/direct_serial.rs b/mavlink-core/src/connection/direct_serial.rs index 341d075ef2..644839416b 100644 --- a/mavlink-core/src/connection/direct_serial.rs +++ b/mavlink-core/src/connection/direct_serial.rs @@ -91,7 +91,7 @@ impl MavConnection for SerialConnection { self.protocol_version = version; } - fn get_protocol_version(&self) -> MavlinkVersion { + fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } } diff --git a/mavlink-core/src/connection/file.rs b/mavlink-core/src/connection/file.rs index d0fcdc9875..12e6bebafa 100644 --- a/mavlink-core/src/connection/file.rs +++ b/mavlink-core/src/connection/file.rs @@ -52,7 +52,7 @@ impl MavConnection for FileConnection { self.protocol_version = version; } - fn get_protocol_version(&self) -> MavlinkVersion { + fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } } diff --git a/mavlink-core/src/connection/mod.rs b/mavlink-core/src/connection/mod.rs index 7aa4ab78ec..9fe6908aa2 100644 --- a/mavlink-core/src/connection/mod.rs +++ b/mavlink-core/src/connection/mod.rs @@ -24,7 +24,7 @@ pub trait MavConnection { fn send(&self, header: &MavHeader, data: &M) -> Result; 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) -> Result { @@ -34,7 +34,7 @@ pub trait MavConnection { /// Read whole frame fn recv_frame(&self) -> Result, 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, diff --git a/mavlink-core/src/connection/tcp.rs b/mavlink-core/src/connection/tcp.rs index 44d3778777..0629039fbf 100644 --- a/mavlink-core/src/connection/tcp.rs +++ b/mavlink-core/src/connection/tcp.rs @@ -108,7 +108,7 @@ impl MavConnection for TcpConnection { self.protocol_version = version; } - fn get_protocol_version(&self) -> MavlinkVersion { + fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } } diff --git a/mavlink-core/src/connection/udp.rs b/mavlink-core/src/connection/udp.rs index b353ea1ba1..c8a3d764c6 100644 --- a/mavlink-core/src/connection/udp.rs +++ b/mavlink-core/src/connection/udp.rs @@ -156,7 +156,7 @@ impl MavConnection for UdpConnection { self.protocol_version = version; } - fn get_protocol_version(&self) -> MavlinkVersion { + fn protocol_version(&self) -> MavlinkVersion { self.protocol_version } } diff --git a/mavlink-core/src/lib.rs b/mavlink-core/src/lib.rs index 29e0d20345..e6e7aec97a 100644 --- a/mavlink-core/src/lib.rs +++ b/mavlink-core/src/lib.rs @@ -221,14 +221,11 @@ impl MavFrame { MavlinkVersion::V1 => buf.get_u8().into(), }; - match M::parse(version, msg_id, buf.remaining_bytes()) { - Ok(msg) => Ok(Self { - header, - msg, - protocol_version: version, - }), - Err(err) => Err(err), - } + M::parse(version, msg_id, buf.remaining_bytes()).map(|msg| Self { + header, + msg, + protocol_version: version, + }) } /// Return the frame header @@ -474,22 +471,18 @@ pub fn read_v1_msg( ) -> Result<(MavHeader, M), error::MessageReadError> { let message = read_v1_raw_message::(r)?; - M::parse( - MavlinkVersion::V1, - u32::from(message.message_id()), - message.payload(), - ) - .map(|msg| { - ( - MavHeader { - sequence: message.sequence(), - system_id: message.system_id(), - component_id: message.component_id(), - }, - msg, - ) - }) - .map_err(|err| err.into()) + Ok(( + MavHeader { + sequence: message.sequence(), + system_id: message.system_id(), + component_id: message.component_id(), + }, + M::parse( + MavlinkVersion::V1, + u32::from(message.message_id()), + message.payload(), + )?, + )) } /// Async read a MAVLink v1 message from a Read stream. @@ -502,22 +495,18 @@ pub async fn read_v1_msg_async( ) -> Result<(MavHeader, M), error::MessageReadError> { let message = read_v1_raw_message_async::(r).await?; - M::parse( - MavlinkVersion::V1, - u32::from(message.message_id()), - message.payload(), - ) - .map(|msg| { - ( - MavHeader { - sequence: message.sequence(), - system_id: message.system_id(), - component_id: message.component_id(), - }, - msg, - ) - }) - .map_err(|err| err.into()) + Ok(( + MavHeader { + sequence: message.sequence(), + system_id: message.system_id(), + component_id: message.component_id(), + }, + M::parse( + MavlinkVersion::V1, + u32::from(message.message_id()), + message.payload(), + )?, + )) } const MAVLINK_IFLAG_SIGNED: u8 = 0x01; @@ -818,18 +807,14 @@ pub fn read_v2_msg( ) -> Result<(MavHeader, M), error::MessageReadError> { let message = read_v2_raw_message::(read)?; - M::parse(MavlinkVersion::V2, message.message_id(), message.payload()) - .map(|msg| { - ( - MavHeader { - sequence: message.sequence(), - system_id: message.system_id(), - component_id: message.component_id(), - }, - msg, - ) - }) - .map_err(|err| err.into()) + Ok(( + MavHeader { + sequence: message.sequence(), + system_id: message.system_id(), + component_id: message.component_id(), + }, + M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?, + )) } /// Async read a MAVLink v2 message from a Read stream. @@ -839,18 +824,14 @@ pub async fn read_v2_msg_async( ) -> Result<(MavHeader, M), error::MessageReadError> { let message = read_v2_raw_message_async::(read).await?; - M::parse(MavlinkVersion::V2, message.message_id(), message.payload()) - .map(|msg| { - ( - MavHeader { - sequence: message.sequence(), - system_id: message.system_id(), - component_id: message.component_id(), - }, - msg, - ) - }) - .map_err(|err| err.into()) + Ok(( + MavHeader { + sequence: message.sequence(), + system_id: message.system_id(), + component_id: message.component_id(), + }, + M::parse(MavlinkVersion::V2, message.message_id(), message.payload())?, + )) } /// Async read a MAVLink v2 message from a Read stream. @@ -863,22 +844,18 @@ pub async fn read_v2_msg_async( ) -> Result<(MavHeader, M), error::MessageReadError> { let message = read_v2_raw_message_async::(r).await?; - M::parse( - MavlinkVersion::V2, - u32::from(message.message_id()), - message.payload(), - ) - .map(|msg| { - ( - MavHeader { - sequence: message.sequence(), - system_id: message.system_id(), - component_id: message.component_id(), - }, - msg, - ) - }) - .map_err(|err| err.into()) + Ok(( + MavHeader { + sequence: message.sequence(), + system_id: message.system_id(), + component_id: message.component_id(), + }, + M::parse( + MavlinkVersion::V2, + u32::from(message.message_id()), + message.payload(), + )?, + )) } /// Write a message using the given mavlink version diff --git a/mavlink/examples/embedded-async-read/src/main.rs b/mavlink/examples/embedded-async-read/src/main.rs index af76a2640a..7f53335de3 100644 --- a/mavlink/examples/embedded-async-read/src/main.rs +++ b/mavlink/examples/embedded-async-read/src/main.rs @@ -82,12 +82,9 @@ pub async fn rx_task(rx: usart::UartRx<'static, Async>) { .unwrap(); rprintln!("Read raw message: msg_id={}", raw.message_id()); - match raw.message_id() { - HEARTBEAT_DATA::ID => { - let heartbeat = HEARTBEAT_DATA::deser(MavlinkVersion::V2, raw.payload()).unwrap(); - rprintln!("heartbeat: {:?}", heartbeat); - } - _ => {} + if raw.message_id() == HEARTBEAT_DATA::ID { + let heartbeat = HEARTBEAT_DATA::deser(MavlinkVersion::V2, raw.payload()).unwrap(); + rprintln!("heartbeat: {:?}", heartbeat); } } }