Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 2 additions & 23 deletions mavlink-bindgen/src/parser.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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::<Vec<MavMessage>>();
// self.messages = msgs;
// self
// }

/// Simple header comment
#[inline(always)]
fn emit_comments(&self, dialect_name: &str) -> TokenStream {
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -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 {})",
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -2089,7 +2069,6 @@ pub fn parse_profile(
}
}

//let profile = profile.update_messages(); //TODO verify no longer needed
Ok(profile.update_enums())
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 {})",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 {})",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 {})",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 {})",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 {})",
Expand Down Expand Up @@ -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 {})",
Expand Down Expand Up @@ -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 {})",
Expand Down Expand Up @@ -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 {})",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 {})",
Expand Down
10 changes: 8 additions & 2 deletions mavlink-core/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,8 @@ impl<M: Message> MavFrame<M> {
///
/// # 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);

Expand Down Expand Up @@ -338,7 +339,12 @@ impl<M: Message> MavFrame<M> {
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"),
);
}
}

Expand Down
Loading