diff --git a/mavlink-bindgen/src/parser.rs b/mavlink-bindgen/src/parser.rs index 10bc4d6c1bd..891aa01caca 100644 --- a/mavlink-bindgen/src/parser.rs +++ b/mavlink-bindgen/src/parser.rs @@ -108,16 +108,6 @@ impl MavProfile { self } - //TODO verify this is no longer necessary since we're supporting both mavlink1 and mavlink2 - // ///If we are not using Mavlink v2, remove messages with id's > 254 - // fn update_messages(mut self) -> Self { - // //println!("Updating messages"); - // let msgs = self.messages.into_iter().filter( - // |x| x.id <= 254).collect::>(); - // self.messages = msgs; - // self - // } - /// Simple header comment #[inline(always)] fn emit_comments(&self, dialect_name: &str) -> TokenStream { @@ -179,7 +169,6 @@ impl MavProfile { } fn emit_rust(&self, dialect_name: &str) -> TokenStream { - //TODO verify that id_width of u8 is OK even in mavlink v1 let id_width = format_ident!("u32"); let comment = self.emit_comments(dialect_name); @@ -927,15 +916,6 @@ impl MavMessage { quote! { let mut __tmp = BytesMut::new(bytes); - // TODO: these lints are produced on a couple of cubepilot messages - // because they are generated as empty structs with no fields and - // therefore Self::ENCODED_LEN is 0. This itself is a bug because - // cubepilot.xml has unclosed tags in fields, which the parser has - // bad time handling. It should probably be fixed in both the parser - // and mavlink message definitions. However, until it's done, let's - // skip the lints. - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", @@ -1025,8 +1005,8 @@ impl MavMessage { let extra_crc = extra_crc(self); let (name_types, payload_encoded_len) = self.emit_name_types(); assert!( - payload_encoded_len <= 255, - "maximum payload length is 255 bytes" + (1..=255).contains(&payload_encoded_len), + "payload length must be between 1 and 255 bytes" ); let deser_vars = self.emit_deserialize_vars(); @@ -2089,7 +2069,6 @@ pub fn parse_profile( } } - //let profile = profile.update_messages(); //TODO verify no longer needed Ok(profile.update_enums()) } diff --git a/mavlink-bindgen/tests/snapshots/e2e_snapshots__deprecated.xml@deprecated.rs.snap b/mavlink-bindgen/tests/snapshots/e2e_snapshots__deprecated.xml@deprecated.rs.snap index e9a4a84b55a..c613d912edb 100644 --- a/mavlink-bindgen/tests/snapshots/e2e_snapshots__deprecated.xml@deprecated.rs.snap +++ b/mavlink-bindgen/tests/snapshots/e2e_snapshots__deprecated.xml@deprecated.rs.snap @@ -133,8 +133,6 @@ impl MessageData for PING_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", diff --git a/mavlink-bindgen/tests/snapshots/e2e_snapshots__heartbeat.xml@heartbeat.rs.snap b/mavlink-bindgen/tests/snapshots/e2e_snapshots__heartbeat.xml@heartbeat.rs.snap index 6aede484b40..3848c2c5496 100644 --- a/mavlink-bindgen/tests/snapshots/e2e_snapshots__heartbeat.xml@heartbeat.rs.snap +++ b/mavlink-bindgen/tests/snapshots/e2e_snapshots__heartbeat.xml@heartbeat.rs.snap @@ -99,8 +99,6 @@ impl MessageData for HEARTBEAT_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", diff --git a/mavlink-bindgen/tests/snapshots/e2e_snapshots__mav_bool.xml@mav_bool.rs.snap b/mavlink-bindgen/tests/snapshots/e2e_snapshots__mav_bool.xml@mav_bool.rs.snap index 41baa22f2d8..85010ccc1cd 100644 --- a/mavlink-bindgen/tests/snapshots/e2e_snapshots__mav_bool.xml@mav_bool.rs.snap +++ b/mavlink-bindgen/tests/snapshots/e2e_snapshots__mav_bool.xml@mav_bool.rs.snap @@ -107,8 +107,6 @@ impl MessageData for BOOL_TEST_MESSAGE_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", diff --git a/mavlink-bindgen/tests/snapshots/e2e_snapshots__no_field_description.xml@no_field_description.rs.snap b/mavlink-bindgen/tests/snapshots/e2e_snapshots__no_field_description.xml@no_field_description.rs.snap index d39b47d5237..5d932faafbf 100644 --- a/mavlink-bindgen/tests/snapshots/e2e_snapshots__no_field_description.xml@no_field_description.rs.snap +++ b/mavlink-bindgen/tests/snapshots/e2e_snapshots__no_field_description.xml@no_field_description.rs.snap @@ -83,8 +83,6 @@ impl MessageData for CUBEPILOT_RAW_RC_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", diff --git a/mavlink-bindgen/tests/snapshots/e2e_snapshots__parameters.xml@parameters.rs.snap b/mavlink-bindgen/tests/snapshots/e2e_snapshots__parameters.xml@parameters.rs.snap index 3823acec175..67e080f53fb 100644 --- a/mavlink-bindgen/tests/snapshots/e2e_snapshots__parameters.xml@parameters.rs.snap +++ b/mavlink-bindgen/tests/snapshots/e2e_snapshots__parameters.xml@parameters.rs.snap @@ -121,8 +121,6 @@ impl MessageData for PARAM_REQUEST_LIST_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", @@ -212,8 +210,6 @@ impl MessageData for PARAM_REQUEST_READ_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", @@ -316,8 +312,6 @@ impl MessageData for PARAM_SET_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", @@ -421,8 +415,6 @@ impl MessageData for PARAM_VALUE_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", diff --git a/mavlink-bindgen/tests/snapshots/e2e_snapshots__superseded.xml@superseded.rs.snap b/mavlink-bindgen/tests/snapshots/e2e_snapshots__superseded.xml@superseded.rs.snap index 60cb5ca2f82..930fd43dc2d 100644 --- a/mavlink-bindgen/tests/snapshots/e2e_snapshots__superseded.xml@superseded.rs.snap +++ b/mavlink-bindgen/tests/snapshots/e2e_snapshots__superseded.xml@superseded.rs.snap @@ -194,8 +194,6 @@ impl MessageData for SMART_BATTERY_INFO_DATA { } fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize { let mut __tmp = BytesMut::new(bytes); - #[allow(clippy::absurd_extreme_comparisons)] - #[allow(unused_comparisons)] if __tmp.remaining() < Self::ENCODED_LEN { panic!( "buffer is too small (need {} bytes, but got {})", diff --git a/mavlink-core/src/lib.rs b/mavlink-core/src/lib.rs index 33ee854cad4..53f754da4f9 100644 --- a/mavlink-core/src/lib.rs +++ b/mavlink-core/src/lib.rs @@ -301,7 +301,8 @@ impl MavFrame { /// /// # Panics /// - /// Will panic if frame does not fit in the provided buffer. + /// - If the frame does not fit in the provided buffer + /// - When attempting to serialize a message with an id greater then 255 with MAVLink 1 pub fn ser(&self, buf: &mut [u8]) -> usize { let mut buf = bytes_mut::BytesMut::new(buf); @@ -338,7 +339,12 @@ impl MavFrame { buf.put_slice(&bytes[..3]); } MavlinkVersion::V1 => { - buf.put_u8(self.msg.message_id() as u8); //TODO check + buf.put_u8( + self.msg + .message_id() + .try_into() + .expect("message is MAVLink 2 only"), + ); } }