From ab925ad8469a1f5668166e0dd23d99883cbc86b7 Mon Sep 17 00:00:00 2001 From: Nazar Serhiichuk <43041209+G1gg1L3s@users.noreply.github.com> Date: Mon, 22 Jul 2024 02:56:52 +0300 Subject: [PATCH] Improve final binary size --- mavlink-bindgen/src/parser.rs | 19 +++++++++++++++++++ mavlink-core/src/bytes.rs | 16 ++++++++++++++++ mavlink-core/src/bytes_mut.rs | 13 +++++++++++++ 3 files changed, 48 insertions(+) diff --git a/mavlink-bindgen/src/parser.rs b/mavlink-bindgen/src/parser.rs index 1a6eaba7e3..1ed238b815 100644 --- a/mavlink-bindgen/src/parser.rs +++ b/mavlink-bindgen/src/parser.rs @@ -502,8 +502,27 @@ 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); + + // 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 {})", + Self::ENCODED_LEN, + __tmp.remaining(), + ) + } + #(#ser_vars)* if matches!(version, MavlinkVersion::V2) { let len = __tmp.len(); diff --git a/mavlink-core/src/bytes.rs b/mavlink-core/src/bytes.rs index 56597f7f59..712ca36623 100644 --- a/mavlink-core/src/bytes.rs +++ b/mavlink-core/src/bytes.rs @@ -13,10 +13,12 @@ impl<'a> Bytes<'a> { self.data.len() - self.pos } + #[inline] pub fn remaining_bytes(&self) -> &'a [u8] { &self.data[self.pos..] } + #[inline] fn check_remaining(&self, count: usize) { assert!( self.remaining() >= count, @@ -26,6 +28,7 @@ impl<'a> Bytes<'a> { ); } + #[inline] pub fn get_bytes(&mut self, count: usize) -> &[u8] { self.check_remaining(count); @@ -34,6 +37,7 @@ impl<'a> Bytes<'a> { bytes } + #[inline] pub fn get_array(&mut self) -> [u8; SIZE] { let bytes = self.get_bytes(SIZE); let mut arr = [0u8; SIZE]; @@ -45,6 +49,7 @@ impl<'a> Bytes<'a> { arr } + #[inline] pub fn get_u8(&mut self) -> u8 { self.check_remaining(1); @@ -53,6 +58,7 @@ impl<'a> Bytes<'a> { val } + #[inline] pub fn get_i8(&mut self) -> i8 { self.check_remaining(1); @@ -61,14 +67,17 @@ impl<'a> Bytes<'a> { val } + #[inline] pub fn get_u16_le(&mut self) -> u16 { u16::from_le_bytes(self.get_array()) } + #[inline] pub fn get_i16_le(&mut self) -> i16 { i16::from_le_bytes(self.get_array()) } + #[inline] pub fn get_u24_le(&mut self) -> u32 { const SIZE: usize = 3; self.check_remaining(SIZE); @@ -81,6 +90,7 @@ impl<'a> Bytes<'a> { u32::from_le_bytes(val) } + #[inline] pub fn get_i24_le(&mut self) -> i32 { const SIZE: usize = 3; self.check_remaining(SIZE); @@ -93,26 +103,32 @@ impl<'a> Bytes<'a> { i32::from_le_bytes(val) } + #[inline] pub fn get_u32_le(&mut self) -> u32 { u32::from_le_bytes(self.get_array()) } + #[inline] pub fn get_i32_le(&mut self) -> i32 { i32::from_le_bytes(self.get_array()) } + #[inline] pub fn get_u64_le(&mut self) -> u64 { u64::from_le_bytes(self.get_array()) } + #[inline] pub fn get_i64_le(&mut self) -> i64 { i64::from_le_bytes(self.get_array()) } + #[inline] pub fn get_f32_le(&mut self) -> f32 { f32::from_le_bytes(self.get_array()) } + #[inline] pub fn get_f64_le(&mut self) -> f64 { f64::from_le_bytes(self.get_array()) } diff --git a/mavlink-core/src/bytes_mut.rs b/mavlink-core/src/bytes_mut.rs index aa01c351a6..1fc22b9cf6 100644 --- a/mavlink-core/src/bytes_mut.rs +++ b/mavlink-core/src/bytes_mut.rs @@ -33,6 +33,7 @@ impl<'a> BytesMut<'a> { ); } + #[inline] pub fn put_slice(&mut self, src: &[u8]) { self.check_remaining(src.len()); @@ -42,6 +43,7 @@ impl<'a> BytesMut<'a> { self.len += src.len(); } + #[inline] pub fn put_u8(&mut self, val: u8) { self.check_remaining(1); @@ -49,6 +51,7 @@ impl<'a> BytesMut<'a> { self.len += 1; } + #[inline] pub fn put_i8(&mut self, val: i8) { self.check_remaining(1); @@ -56,6 +59,7 @@ impl<'a> BytesMut<'a> { self.len += 1; } + #[inline] pub fn put_u16_le(&mut self, val: u16) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE); @@ -65,6 +69,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_i16_le(&mut self, val: i16) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE); @@ -74,6 +79,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_u24_le(&mut self, val: u32) { const SIZE: usize = 3; const MAX: u32 = 2u32.pow(24) - 1; @@ -91,6 +97,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_i24_le(&mut self, val: i32) { const SIZE: usize = 3; const MIN: i32 = 2i32.pow(23); @@ -116,6 +123,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_u32_le(&mut self, val: u32) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE); @@ -125,6 +133,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_i32_le(&mut self, val: i32) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE); @@ -134,6 +143,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_u64_le(&mut self, val: u64) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE); @@ -143,6 +153,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_i64_le(&mut self, val: i64) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE); @@ -152,6 +163,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_f32_le(&mut self, val: f32) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE); @@ -161,6 +173,7 @@ impl<'a> BytesMut<'a> { self.len += SIZE; } + #[inline] pub fn put_f64_le(&mut self, val: f64) { const SIZE: usize = core::mem::size_of::(); self.check_remaining(SIZE);