diff --git a/mavlink-bindgen/src/lib.rs b/mavlink-bindgen/src/lib.rs
index 22f1efa2ce1c00b1fa812c094bc625f3415981b7..23aae4b1d0e6fc3f58ad4d1efb3b9fad75870e88 100644
--- a/mavlink-bindgen/src/lib.rs
+++ b/mavlink-bindgen/src/lib.rs
@@ -39,7 +39,7 @@ fn _generate(
 ) -> Result<GeneratedBindings, BindGenError> {
     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 2b45e5d17b8f7e5afa00c4a0ac1bb7871ea7411a..dd8e389ea1358ae962701c7db3df372ce6194b12 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<MavType>, usize),
 }
 
-impl Default for MavType {
-    fn default() -> Self {
-        Self::UInt8
-    }
-}
-
 impl MavType {
     fn parse_type(s: &str) -> Option<Self> {
         use self::MavType::*;
diff --git a/mavlink-core/src/connection/direct_serial.rs b/mavlink-core/src/connection/direct_serial.rs
index 341d075ef25cc41755cddf25629d78bca199e4d6..a3a33a0fa6a7d9f8e09c86f23a8c30a76594e3fe 100644
--- a/mavlink-core/src/connection/direct_serial.rs
+++ b/mavlink-core/src/connection/direct_serial.rs
@@ -1,3 +1,5 @@
+//! Serial MAVLINK connection
+
 use crate::connection::MavConnection;
 use crate::peek_reader::PeekReader;
 use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message};
@@ -8,8 +10,6 @@ use std::sync::Mutex;
 use crate::error::{MessageReadError, MessageWriteError};
 use serial::{prelude::*, SystemPort};
 
-/// Serial MAVLINK connection
-
 pub fn open(settings: &str) -> io::Result<SerialConnection> {
     let settings_toks: Vec<&str> = settings.split(':').collect();
     if settings_toks.len() < 2 {
@@ -19,15 +19,15 @@ pub fn open(settings: &str) -> io::Result<SerialConnection> {
         ));
     }
 
-    let baud_opt = settings_toks[1].parse::<usize>();
-    if baud_opt.is_err() {
+    let Ok(baud) = settings_toks[1]
+        .parse::<usize>()
+        .map(serial::core::BaudRate::from_speed)
+    else {
         return Err(io::Error::new(
             io::ErrorKind::AddrNotAvailable,
             "Invalid baud rate",
         ));
-    }
-
-    let baud = serial::core::BaudRate::from_speed(baud_opt.unwrap());
+    };
 
     let settings = serial::core::PortSettings {
         baud_rate: baud,
@@ -91,7 +91,7 @@ impl<M: Message> MavConnection<M> 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 d0fcdc987520c7128df3c6b61db3881d85ab0c3d..85444bb6ae9981909cec2b7fdfd62306b0eb03ff 100644
--- a/mavlink-core/src/connection/file.rs
+++ b/mavlink-core/src/connection/file.rs
@@ -1,3 +1,5 @@
+//! File MAVLINK connection
+
 use crate::connection::MavConnection;
 use crate::error::{MessageReadError, MessageWriteError};
 use crate::peek_reader::PeekReader;
@@ -7,8 +9,6 @@ use std::fs::File;
 use std::io;
 use std::sync::Mutex;
 
-/// File MAVLINK connection
-
 pub fn open(file_path: &str) -> io::Result<FileConnection> {
     let file = File::open(file_path)?;
 
@@ -52,7 +52,7 @@ impl<M: Message> MavConnection<M> 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 7aa4ab78ec5d4122b3523633c2bafb8402ab0f4a..035f63eb289381e8e8ce3ac8ce23afe9b6d3b2a3 100644
--- a/mavlink-core/src/connection/mod.rs
+++ b/mavlink-core/src/connection/mod.rs
@@ -24,7 +24,7 @@ pub trait MavConnection<M: Message> {
     fn send(&self, header: &MavHeader, data: &M) -> Result<usize, crate::error::MessageWriteError>;
 
     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<M>) -> Result<usize, crate::error::MessageWriteError> {
@@ -34,7 +34,7 @@ pub trait MavConnection<M: Message> {
     /// Read whole frame
     fn recv_frame(&self) -> Result<MavFrame<M>, 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,
@@ -107,14 +107,8 @@ pub fn connect<M: Message>(address: &str) -> io::Result<Box<dyn MavConnection<M>
 pub(crate) fn get_socket_addr<T: std::net::ToSocketAddrs>(
     address: T,
 ) -> Result<std::net::SocketAddr, io::Error> {
-    let addr = match address.to_socket_addrs()?.next() {
-        Some(addr) => addr,
-        None => {
-            return Err(io::Error::new(
-                io::ErrorKind::Other,
-                "Host address lookup failed",
-            ));
-        }
-    };
-    Ok(addr)
+    address.to_socket_addrs()?.next().ok_or(io::Error::new(
+        io::ErrorKind::Other,
+        "Host address lookup failed",
+    ))
 }
diff --git a/mavlink-core/src/connection/tcp.rs b/mavlink-core/src/connection/tcp.rs
index 44d37787772b6e93562fce18ac1e1362011eeb38..35b7f09084cb4b7d260a4359fcf135d9eb72a8b1 100644
--- a/mavlink-core/src/connection/tcp.rs
+++ b/mavlink-core/src/connection/tcp.rs
@@ -1,3 +1,5 @@
+//! TCP MAVLink connection
+
 use crate::connection::MavConnection;
 use crate::peek_reader::PeekReader;
 use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message};
@@ -10,8 +12,6 @@ use std::time::Duration;
 
 use super::get_socket_addr;
 
-/// TCP MAVLink connection
-
 pub fn select_protocol<M: Message>(
     address: &str,
 ) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
@@ -108,7 +108,7 @@ impl<M: Message> MavConnection<M> 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 b353ea1ba18f71e8b50e93fd836166f5c1e7e265..3ec739d3f5ecce19d5c2cd119f1722ea9dc7f1ce 100644
--- a/mavlink-core/src/connection/udp.rs
+++ b/mavlink-core/src/connection/udp.rs
@@ -1,3 +1,5 @@
+//! UDP MAVLink connection
+
 use std::collections::VecDeque;
 
 use crate::connection::MavConnection;
@@ -11,8 +13,6 @@ use std::sync::Mutex;
 
 use super::get_socket_addr;
 
-/// UDP MAVLink connection
-
 pub fn select_protocol<M: Message>(
     address: &str,
 ) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
@@ -156,7 +156,7 @@ impl<M: Message> MavConnection<M> 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 29e0d203450b5910d9c464305adeb212677ccf49..e6e7aec97a20fcca7476b7d099a88b2551b5c62c 100644
--- a/mavlink-core/src/lib.rs
+++ b/mavlink-core/src/lib.rs
@@ -221,14 +221,11 @@ impl<M: Message> MavFrame<M> {
             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<M: Message, R: Read>(
 ) -> Result<(MavHeader, M), error::MessageReadError> {
     let message = read_v1_raw_message::<M, _>(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<M: Message>(
 ) -> Result<(MavHeader, M), error::MessageReadError> {
     let message = read_v1_raw_message_async::<M>(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<M: Message, R: Read>(
 ) -> Result<(MavHeader, M), error::MessageReadError> {
     let message = read_v2_raw_message::<M, _>(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<M: Message, R: tokio::io::AsyncReadExt + Unpin>(
 ) -> Result<(MavHeader, M), error::MessageReadError> {
     let message = read_v2_raw_message_async::<M, _>(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<M: Message, R: embedded_io_async::Read>(
 ) -> Result<(MavHeader, M), error::MessageReadError> {
     let message = read_v2_raw_message_async::<M>(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 af76a2640a42553364498b2774e1a793c6cbe0a5..7f53335de3e15e44108646aa00ed6a3b47901f25 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);
         }
     }
 }