diff --git a/.travis.yml b/.travis.yml
index 5b0e032f18443214d0c1e82354bb759462dba49c..a448e6e7001eca2719618eb153115ec6aad2b645 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -1,2 +1,5 @@
 language: rust
 cache: cargo
+script:
+  - cargo build --verbose --all-features
+  - cargo test --verbose --all-features
diff --git a/Cargo.toml b/Cargo.toml
index c6702e3a94033a4dbc524bfb5c2e11a3af35245e..87d3cdec9834a46daf2321e80f53b129a423c873 100644
--- a/Cargo.toml
+++ b/Cargo.toml
@@ -1,8 +1,8 @@
 
 [package]
 name = "mavlink"
-version = "0.7.0"
-authors = ["Todd Stellanova", "Michal Podhradsky", "Kevin Mehall", "Tim Ryan", "Patrick José Pereira"]
+version = "0.8.0"
+authors = ["Todd Stellanova", "Michal Podhradsky", "Kevin Mehall", "Tim Ryan", "Patrick José Pereira", "Ibiyemi Abiodun"]
 build = "build/main.rs"
 description = "Implements the MAVLink data interchange format for UAVs."
 readme = "README.md"
@@ -15,12 +15,12 @@ crc16 = "0.3.3"
 bytes = "0.4"
 xml-rs = "0.2"
 quote = "0.3"
-rustfmt = "0.9"
 lazy_static = "1.2.0"
-serde = { version = "1.0.101", optional = true }
+serde = { version = "1.0.101", optional = true, features = ["derive"] }
 
 [[bin]]
 name = "mavlink-dump"
+required-features = ["common"]
 
 [dependencies]
 crc16 = "0.3.3"
@@ -30,17 +30,33 @@ num-derive = "0.2"
 bitflags = "1.0.4"
 serial = { version = "0.4", optional = true }
 serde = { version = "1.0.101", optional = true }
-
-[dependencies.byteorder]
-version = "0.5.3"
-optional = true
-
+byteorder = { version = "0.5", optional = true }
 
 [features]
+"ardupilotmega" = []
+"asluav" = []
+"autoquad" = []
+"matrixpilot" = []
+"minimal" = []
+"paparazzi" = []
+"python_array_test" = []
+"slugs" = []
+"standard" = []
+"test" = []
+"ualberta" = []
+"uavionix" = []
+"icarous" = []
+"common" = []
+
 "emit-description" = []
 "emit-extensions" = []
 "std" = ["byteorder"]
 "udp" = []
 "tcp" = []
 "direct-serial" = []
-default= ["std", "tcp", "udp", "direct-serial", "serial", "serde"]
+default= ["std", "tcp", "udp", "direct-serial", "serial", "serde", "common"]
+
+# build with all features on docs.rs so that users viewing documentation
+# can see everything
+[package.metadata.docs.rs]
+all-features = true
diff --git a/README.md b/README.md
index 4bbd9727e34ab44920c435275b0cdf29fc8f15f7..aec2ba4e914764a7aa192c068efdd5e0c5b9b013 100644
--- a/README.md
+++ b/README.md
@@ -5,12 +5,12 @@
 [![Documentation](https://docs.rs/mavlink/badge.svg)](https://docs.rs/mavlink)
 
 Rust implementation of the [MAVLink](http://qgroundcontrol.org/mavlink/start) UAV messaging protocol,
-with bindings for the [common message set](http://mavlink.org/messages/common).
+with bindings for all message sets.
 
 Add to your Cargo.toml:
 
 ```
-mavlink = "0.7"
+mavlink = "0.8"
 ```
 
 ## Examples
diff --git a/build/binder.rs b/build/binder.rs
new file mode 100644
index 0000000000000000000000000000000000000000..41529634f0b6d6fa84ae46af5648d3c5ae2361cb
--- /dev/null
+++ b/build/binder.rs
@@ -0,0 +1,27 @@
+use quote::Ident;
+use std::io::Write;
+
+pub fn generate<W: Write>(modules: Vec<String>, out: &mut W) {
+    let modules_tokens = modules.into_iter().map(|module| {
+        let file_name = module.clone() + ".rs";
+        let module_ident = Ident::from(module.clone());
+
+        quote! {
+            #[allow(non_camel_case_types)]
+            #[allow(non_snake_case)]
+            #[allow(unused_variables)]
+            #[allow(unused_mut)]
+            #[cfg(feature = #module)]
+            pub mod #module_ident {
+                use crate::MavlinkVersion; //TODO verify
+                include!(#file_name);
+            }
+        }
+    });
+
+    let tokens = quote! {
+        #(#modules_tokens)*
+    };
+
+    writeln!(out, "{}", tokens).unwrap();
+}
diff --git a/build/main.rs b/build/main.rs
index dc852fdb2ce1bc42918c26e0c69ea4e62f6f8149..4dc0acb4d3958f37c89380d3ed73e04c34208b09 100644
--- a/build/main.rs
+++ b/build/main.rs
@@ -1,14 +1,17 @@
-#![recursion_limit="256"]
+#![recursion_limit = "256"]
 #[macro_use]
 extern crate quote;
 
 extern crate crc16;
 extern crate xml;
 
+mod binder;
 mod parser;
+mod util;
 
+use crate::util::to_module_name;
 use std::env;
-use std::fs::File;
+use std::fs::{read_dir, File};
 use std::path::{Path, PathBuf};
 use std::process::Command;
 
@@ -23,28 +26,89 @@ pub fn main() {
         .current_dir(&src_dir)
         .status()
     {
-        Ok(content) => println!("{}", content),
+        Ok(_) => {}
         Err(error) => eprintln!("{}", error),
     }
 
+    // find & apply patches to XML definitions to avoid crashes
+    let mut patch_dir = src_dir.to_path_buf();
+    patch_dir.push("build/patches");
+    let mut mavlink_dir = src_dir.to_path_buf();
+    mavlink_dir.push("mavlink");
+
+    if let Ok(dir) = read_dir(patch_dir) {
+        for entry in dir {
+            if let Ok(entry) = entry {
+                match Command::new("git")
+                    .arg("apply")
+                    .arg(entry.path().as_os_str())
+                    .current_dir(&mavlink_dir)
+                    .status()
+                {
+                    Ok(_) => (),
+                    Err(error) => eprintln!("{}", error),
+                }
+            }
+        }
+    }
+
     let mut definitions_dir = src_dir.to_path_buf();
     definitions_dir.push("mavlink/message_definitions/v1.0");
-    let definition_file = PathBuf::from("common.xml");
-    let mut definition_rs = definition_file.clone();
-    definition_rs.set_extension("rs");
-
-    let in_path = Path::new(&definitions_dir).join(&definition_file);
-    let mut inf = File::open(&in_path).unwrap();
 
     let out_dir = env::var("OUT_DIR").unwrap();
-    let dest_path = Path::new(&out_dir).join(definition_rs);
-    let mut outf = File::create(&dest_path).unwrap();
 
-    parser::generate(&mut inf, &mut outf);
+    let mut modules = vec![];
+
+    for entry in read_dir(&definitions_dir).expect("could not read definitions directory") {
+        let entry = entry.expect("could not read directory entry");
+
+        let definition_file = entry.file_name();
+        let module_name = to_module_name(&definition_file);
+
+        let mut definition_rs = PathBuf::from(&module_name);
+        definition_rs.set_extension("rs");
+
+        modules.push(module_name);
+
+        let in_path = Path::new(&definitions_dir).join(&definition_file);
+        let mut inf = File::open(&in_path).unwrap();
 
-    // Re-run build if common.xml changes
-    println!(
-        "cargo:rerun-if-changed={}",
-        definition_file.file_name().unwrap().to_str().unwrap()
-    );
+        let dest_path = Path::new(&out_dir).join(definition_rs);
+        let mut outf = File::create(&dest_path).unwrap();
+
+        // generate code
+        parser::generate(&mut inf, &mut outf);
+
+        // format code
+        match Command::new("rustfmt")
+            .arg(dest_path.as_os_str())
+            .current_dir(&out_dir)
+            .status()
+        {
+            Ok(_) => (),
+            Err(error) => eprintln!("{}", error),
+        }
+
+        // Re-run build if common.xml changes
+        println!("cargo:rerun-if-changed={}", entry.path().to_string_lossy());
+    }
+
+    // output mod.rs
+    {
+        let dest_path = Path::new(&out_dir).join("mod.rs");
+        let mut outf = File::create(&dest_path).unwrap();
+
+        // generate code
+        binder::generate(modules, &mut outf);
+
+        // format code
+        match Command::new("rustfmt")
+            .arg(dest_path.as_os_str())
+            .current_dir(&out_dir)
+            .status()
+        {
+            Ok(_) => (),
+            Err(error) => eprintln!("{}", error),
+        }
+    }
 }
diff --git a/build/parser.rs b/build/parser.rs
index af96f7764c20adc14c410b7688dd1046da984ef8..10cf4d28be033f61324d58cc0928436d0d0f1b9b 100644
--- a/build/parser.rs
+++ b/build/parser.rs
@@ -8,8 +8,9 @@ use xml::reader::{EventReader, XmlEvent};
 
 use quote::{Ident, Tokens};
 
+use crate::util::to_module_name;
 #[cfg(feature = "serde")]
-use serde::{Serialize, Deserialize};
+use serde::{Deserialize, Serialize};
 
 #[derive(Debug, PartialEq, Clone, Default)]
 #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
@@ -47,14 +48,14 @@ impl MavProfile {
     }
 
     //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
-//    }
+    //    ///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
     fn emit_comments(&self) -> Ident {
@@ -63,6 +64,14 @@ impl MavProfile {
         ))
     }
 
+    /// Emit includes
+    fn emit_includes(&self) -> Vec<Ident> {
+        self.includes
+            .iter()
+            .map(|i| Ident::from(to_module_name(i)))
+            .collect::<Vec<Ident>>()
+    }
+
     /// Emit rust messages
     fn emit_msgs(&self) -> Vec<Tokens> {
         self.messages
@@ -71,13 +80,11 @@ impl MavProfile {
             .collect::<Vec<Tokens>>()
     }
 
-    /// Emit rust enus
+    /// Emit rust enums
     fn emit_enums(&self) -> Vec<Tokens> {
         self.enums
             .iter()
-            .map(|d| {
-                d.emit_rust()
-            })
+            .map(|d| d.emit_rust())
             .collect::<Vec<Tokens>>()
     }
 
@@ -123,30 +130,51 @@ impl MavProfile {
     }
 
     fn emit_rust(&self) -> Tokens {
+        //TODO verify that id_width of u8 is OK even in mavlink v1
+        let id_width = Ident::from("u32");
+
         let comment = self.emit_comments();
         let msgs = self.emit_msgs();
+        let includes = self.emit_includes();
         let enum_names = self.emit_enum_names();
         let struct_names = self.emit_struct_names();
         let enums = self.emit_enums();
         let msg_ids = self.emit_msg_ids();
         let msg_crc = self.emit_msg_crc();
-        let mav_message = self.emit_mav_message(enum_names.clone(), struct_names.clone());
-        let mav_message_parse =
-            self.emit_mav_message_parse(enum_names.clone(), struct_names.clone(), msg_ids.clone());
-        let mav_message_id = self.emit_mav_message_id(enum_names.clone(), msg_ids.clone());
-        let mav_message_id_from_name = self.emit_mav_message_id_from_name(enum_names.clone(), msg_ids.clone());
-        let mav_message_serialize = self.emit_mav_message_serialize(enum_names);
-
-        //TODO verify that id_width of u8 is OK even in mavlink v1
-        let id_width = Ident::from("u32");
 
-        quote!{
+        let mav_message =
+            self.emit_mav_message(enum_names.clone(), struct_names.clone(), includes.clone());
+        let mav_message_parse = self.emit_mav_message_parse(
+            enum_names.clone(),
+            struct_names.clone(),
+            msg_ids.clone(),
+            includes.clone(),
+        );
+        let mav_message_crc = self.emit_mav_message_crc(
+            id_width.clone(),
+            msg_ids.clone(),
+            msg_crc.clone(),
+            includes.clone(),
+        );
+        let mav_message_id =
+            self.emit_mav_message_id(enum_names.clone(), msg_ids.clone(), includes.clone());
+        let mav_message_id_from_name = self.emit_mav_message_id_from_name(
+            enum_names.clone(),
+            msg_ids.clone(),
+            includes.clone(),
+        );
+        let mav_message_serialize = self.emit_mav_message_serialize(enum_names, includes.clone());
+
+        quote! {
             #comment
             use bytes::{Buf, BufMut, Bytes, IntoBuf};
-            use num_derive::FromPrimitive;    
+            use num_derive::FromPrimitive;
             use num_traits::FromPrimitive;
             use bitflags::bitflags;
 
+            use crate::Message;
+            use crate::{#(#includes::*),*};
+
             #[cfg(feature = "serde")]
             use serde::{Serialize, Deserialize};
 
@@ -160,28 +188,35 @@ impl MavProfile {
             #[derive(Clone, PartialEq, Debug)]
             #mav_message
 
-            impl MavMessage {
+            impl Message for MavMessage {
                 #mav_message_parse
                 #mav_message_id
                 #mav_message_id_from_name
                 #mav_message_serialize
-                pub fn extra_crc(id: #id_width) -> u8 {
-                    match id {
-                        #(#msg_ids => #msg_crc,)*
-                        _ => 0,
-                    }
-                }
+                #mav_message_crc
             }
         }
     }
 
-    fn emit_mav_message(&self, enums: Vec<Tokens>, structs: Vec<Tokens>) -> Tokens {
-        quote!{
-                #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
-                #[cfg_attr(feature = "serde", serde(tag = "type"))]
-                pub enum MavMessage {
-                    #(#enums(#structs)),*
-                }
+    fn emit_mav_message(
+        &self,
+        enums: Vec<Tokens>,
+        structs: Vec<Tokens>,
+        includes: Vec<Ident>,
+    ) -> Tokens {
+        let includes = includes.into_iter().map(|include| {
+            quote! {
+                #include(crate::#include::MavMessage)
+            }
+        });
+
+        quote! {
+            #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
+            #[cfg_attr(feature = "serde", serde(tag = "type"))]
+            pub enum MavMessage {
+                #(#enums(#structs),)*
+                #(#includes,)*
+            }
         }
     }
 
@@ -190,51 +225,123 @@ impl MavProfile {
         enums: Vec<Tokens>,
         structs: Vec<Tokens>,
         ids: Vec<Tokens>,
+        includes: Vec<Ident>,
     ) -> Tokens {
         let id_width = Ident::from("u32");
-        quote!{
-            pub fn parse(version: MavlinkVersion, id: #id_width, payload: &[u8]) -> Option<MavMessage> {
+
+        // try parsing all included message variants if it doesn't land in the id
+        // range for this message
+        let includes_branches = includes.into_iter().map(|i| {
+            quote! {
+                if let Some(msg) = crate::#i::MavMessage::parse(version, id, payload) {
+                    return Some(MavMessage::#i(msg))
+                }
+            }
+        });
+
+        quote! {
+            fn parse(version: MavlinkVersion, id: #id_width, payload: &[u8]) -> Option<MavMessage> {
                 match id {
-                    #(#ids => Some(MavMessage::#enums(#structs::deser(version, payload).unwrap())),)*
-                    _ => None,
+                    #(#ids => #structs::deser(version, payload).map(|s| MavMessage::#enums(s)),)*
+                    _ => {
+                        #(#includes_branches)*
+                        None
+                    },
                 }
             }
         }
     }
 
-    fn emit_mav_message_id(&self, enums: Vec<Tokens>, ids: Vec<Tokens>) -> Tokens {
+    fn emit_mav_message_crc(
+        &self,
+        id_width: Ident,
+        ids: Vec<Tokens>,
+        crc: Vec<Tokens>,
+        includes: Vec<Ident>,
+    ) -> Tokens {
+        let includes_branch = includes.into_iter().map(|include| {
+            quote! {
+                match crate::#include::MavMessage::extra_crc(id) {
+                    0 => {},
+                    any => return any
+                }
+            }
+        });
+
+        quote! {
+            fn extra_crc(id: #id_width) -> u8 {
+                match id {
+                    #(#ids => #crc,)*
+                    _ => {
+                        #(#includes_branch)*
+
+                        0
+                    },
+                }
+            }
+        }
+    }
+
+    fn emit_mav_message_id(
+        &self,
+        enums: Vec<Tokens>,
+        ids: Vec<Tokens>,
+        includes: Vec<Ident>,
+    ) -> Tokens {
         let id_width = Ident::from("u32");
-        quote!{
-            pub fn message_id(&self) -> #id_width {
+        quote! {
+            fn message_id(&self) -> #id_width {
                 match self {
                     #(MavMessage::#enums(..) => #ids,)*
+                    #(MavMessage::#includes(msg) => msg.message_id(),)*
                 }
             }
         }
     }
 
-    fn emit_mav_message_id_from_name(&self, enums: Vec<Tokens>, ids: Vec<Tokens>) -> Tokens {
-        let enum_names = enums.iter()
+    fn emit_mav_message_id_from_name(
+        &self,
+        enums: Vec<Tokens>,
+        ids: Vec<Tokens>,
+        includes: Vec<Ident>,
+    ) -> Tokens {
+        let includes_branch = includes.into_iter().map(|include| {
+            quote! {
+                match crate::#include::MavMessage::message_id_from_name(name) {
+                    Ok(name) => return Ok(name),
+                    Err(..) => {}
+                }
+            }
+        });
+
+        let enum_names = enums
+            .iter()
             .map(|enum_name| {
                 let name = Ident::from(format!("\"{}\"", enum_name));
                 quote!(#name)
-            }).collect::<Vec<Tokens>>();
+            })
+            .collect::<Vec<Tokens>>();
 
-        quote!{
-            pub fn message_id_from_name(name: &str) -> Result<u32, &'static str> {
+        quote! {
+            fn message_id_from_name(name: &str) -> Result<u32, &'static str> {
                 match name {
                     #(#enum_names => Ok(#ids),)*
-                    _ => Err("Invalid message name."),
+                    _ => {
+                        #(#includes_branch)*
+
+                        Err("Invalid message name.")
+                    }
                 }
             }
         }
     }
 
-    fn emit_mav_message_serialize(&self, enums: Vec<Tokens>) -> Tokens {
-        quote!{
-            pub fn ser(&self) -> Vec<u8> {
+    fn emit_mav_message_serialize(&self, enums: Vec<Tokens>, includes: Vec<Ident>) -> Tokens {
+        quote! {
+            fn ser(&self) -> Vec<u8> {
                 match self {
                     #(&MavMessage::#enums(ref body) => body.ser(),)*
+                    #(&MavMessage::#includes(ref msg) => msg.ser(),)*
                 }
             }
         }
@@ -291,7 +398,7 @@ impl MavEnum {
         let enum_def;
         if let Some(width) = self.bitfield.clone() {
             let width = Ident::from(width);
-            enum_def = quote!{
+            enum_def = quote! {
                 bitflags!{
                     #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
                     pub struct #enum_name: #width {
@@ -300,7 +407,7 @@ impl MavEnum {
                 }
             };
         } else {
-            enum_def = quote!{
+            enum_def = quote! {
                 #[derive(Debug, Copy, Clone, PartialEq, FromPrimitive)]
                 #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
                 #[cfg_attr(feature = "serde", serde(tag = "type"))]
@@ -310,7 +417,7 @@ impl MavEnum {
             };
         }
 
-        quote!{
+        quote! {
             #enum_def
 
             impl Default for #enum_name {
@@ -350,11 +457,12 @@ impl MavMessage {
 
     fn emit_name_types(&self) -> (Vec<Tokens>, usize) {
         let mut encoded_payload_len: usize = 0;
-        let field_toks = self.fields
+        let field_toks = self
+            .fields
             .iter()
             .map(|field| {
                 let nametype = field.emit_name_type();
-                encoded_payload_len +=  field.mavtype.len();
+                encoded_payload_len += field.mavtype.len();
 
                 #[cfg(feature = "emit-description")]
                 let description = self.emit_description();
@@ -362,7 +470,7 @@ impl MavMessage {
                 #[cfg(not(feature = "emit-description"))]
                 let description = Ident::from("");
 
-                quote!{
+                quote! {
                     #description
                     #nametype
                 }
@@ -376,57 +484,59 @@ impl MavMessage {
     fn emit_description(&self) -> Tokens {
         let mut desc = String::from(format!("\n/// id: {}\n", self.id));
         if let Some(val) = self.description.clone() {
-            desc = desc + &format!("/// {}.\n",val);
+            desc = desc + &format!("/// {}.\n", val);
         }
         let desc = Ident::from(desc);
         quote!(#desc)
     }
 
     fn emit_serialize_vars(&self) -> Tokens {
-        let ser_vars = self.fields.iter()
-            .map(|f| {
-                f.rust_writer()
-            }).collect::<Vec<Tokens>>();
-            quote!{
-                let mut _tmp = Vec::new();
-                #(#ser_vars)*
-                _tmp
-            }
+        let ser_vars = self
+            .fields
+            .iter()
+            .map(|f| f.rust_writer())
+            .collect::<Vec<Tokens>>();
+        quote! {
+            let mut _tmp = Vec::new();
+            #(#ser_vars)*
+            _tmp
+        }
     }
 
     fn emit_deserialize_vars(&self) -> Tokens {
-        let deser_vars = self.fields.iter()
-            .map(|f| {
-                f.rust_reader()
-            }).collect::<Vec<Tokens>>();
+        let deser_vars = self
+            .fields
+            .iter()
+            .map(|f| f.rust_reader())
+            .collect::<Vec<Tokens>>();
 
-            let encoded_len_name = Ident::from(format!("{}_DATA::ENCODED_LEN", self.name));
+        let encoded_len_name = Ident::from(format!("{}_DATA::ENCODED_LEN", self.name));
 
-            if deser_vars.is_empty() {
-                // struct has no fields
-                quote!{
-                    Some(Self::default())
+        if deser_vars.is_empty() {
+            // struct has no fields
+            quote! {
+                Some(Self::default())
+            }
+        } else {
+            quote! {
+                let avail_len = _input.len();
+
+                //fast zero copy
+                let mut buf = Bytes::from(_input).into_buf();
+
+                // handle payload length truncuation due to empty fields
+                if avail_len < #encoded_len_name {
+                    //copy available bytes into an oversized buffer filled with zeros
+                    let mut payload_buf  = [0; #encoded_len_name];
+                    payload_buf[0..avail_len].copy_from_slice(_input);
+                    buf = Bytes::from(&payload_buf[..]).into_buf();
                 }
-            } else {
-                quote!{
-                    let avail_len = _input.len();
-
-                    //fast zero copy
-                    let mut buf = Bytes::from(_input).into_buf();
-
-                    // handle payload length truncuation due to empty fields
-                    if avail_len < #encoded_len_name {
-                        //copy available bytes into an oversized buffer filled with zeros
-                        let mut payload_buf  = [0; #encoded_len_name];
-                        payload_buf[0..avail_len].copy_from_slice(_input);
-                        buf = Bytes::from(&payload_buf[..]).into_buf();
-                    }
 
-                    let mut _struct = Self::default();
-                    #(#deser_vars)*
-                    Some(_struct)
-                }
+                let mut _struct = Self::default();
+                #(#deser_vars)*
+                Some(_struct)
             }
+        }
     }
 
     fn emit_rust(&self) -> Tokens {
@@ -442,7 +552,7 @@ impl MavMessage {
         #[cfg(not(feature = "emit-description"))]
         let description = Ident::from("");
 
-        quote!{
+        quote! {
             #description
             #[derive(Debug, Clone, PartialEq, Default)]
             #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
@@ -489,16 +599,14 @@ impl MavField {
             MavType::Array(_, _) => {
                 mavtype = Ident::from(self.mavtype.rust_type());
             }
-            _ => {
-                match self.enumtype {
-                    Some(ref enumname) => {
-                        mavtype = Ident::from(enumname.clone());
-                    }
-                    _ => {
-                        mavtype = Ident::from(self.mavtype.rust_type());
-                    }
+            _ => match self.enumtype {
+                Some(ref enumname) => {
+                    mavtype = Ident::from(enumname.clone());
                 }
-            }
+                _ => {
+                    mavtype = Ident::from(self.mavtype.rust_type());
+                }
+            },
         }
         quote!(#mavtype)
     }
@@ -508,7 +616,7 @@ impl MavField {
     fn emit_description(&self) -> Tokens {
         let mut desc = Vec::new();
         if let Some(val) = self.description.clone() {
-            desc.push(format!("\n/// {}.",val));
+            desc.push(format!("\n/// {}.", val));
         }
         desc.push("\n".to_string());
         let desc: String = desc.iter().map(|s| s.to_string()).collect();
@@ -519,11 +627,10 @@ impl MavField {
     /// Combine rust name and type of a given field
     fn emit_name_type(&self) -> Tokens {
         let name = self.emit_name();
-        let fieldtype = self.emit_type(); 
+        let fieldtype = self.emit_type();
         quote!(pub #name: #fieldtype,)
     }
 
-
     /// Emit writer
     fn rust_writer(&self) -> Tokens {
         let mut name = "self.".to_string() + &self.name.clone();
@@ -538,8 +645,9 @@ impl MavField {
                 }
             } else {
                 match self.mavtype {
-                    MavType::Array(_, _) => {}, // cast are not necessary for arrays
-                    _ => { // an enum, have to use "*foo as u8" cast
+                    MavType::Array(_, _) => {} // cast are not necessary for arrays
+                    _ => {
+                        // an enum, have to use "*foo as u8" cast
                         name += " as ";
                         name += &self.mavtype.rust_type();
                     }
@@ -559,13 +667,14 @@ impl MavField {
             if let Some(dsp) = &self.display {
                 if dsp == "bitmask" {
                     // bitflags
-                    let tmp = self.mavtype.rust_reader(Ident::from("let tmp"), buf.clone());
+                    let tmp = self
+                        .mavtype
+                        .rust_reader(Ident::from("let tmp"), buf.clone());
                     let enum_name = Ident::from(enum_name.clone());
-                    quote!{
+                    quote! {
                         #tmp
                         #name = #enum_name::from_bits(tmp & #enum_name::all().bits()).expect(&format!("Unexpected flags value {}", tmp));
                     }
-
                 } else {
                     panic!("Display option not implemented");
                 }
@@ -574,11 +683,12 @@ impl MavField {
                     MavType::Array(_t, _size) => {
                         return self.mavtype.rust_reader(name, buf);
                     }
-                    _ => {
-                    }
+                    _ => {}
                 }
                 // handle enum by FromPrimitive
-                let tmp = self.mavtype.rust_reader(Ident::from("let tmp"), buf.clone());
+                let tmp = self
+                    .mavtype
+                    .rust_reader(Ident::from("let tmp"), buf.clone());
                 let val = Ident::from("from_".to_string() + &self.mavtype.rust_type());
                 quote!(
                     #tmp
@@ -649,23 +759,23 @@ impl MavType {
     pub fn rust_reader(&self, val: Ident, buf: Ident) -> Tokens {
         use self::MavType::*;
         match self.clone() {
-            Char => quote!{#val = #buf.get_u8() as char;},
-            UInt8 => quote!{#val = #buf.get_u8();},
-            UInt16 => quote!{#val = #buf.get_u16_le();},
-            UInt32 => quote!{#val = #buf.get_u32_le();},
-            UInt64 => quote!{#val = #buf.get_u64_le();},
-            UInt8MavlinkVersion => quote!{#val = #buf.get_u8();},
-            Int8 => quote!{#val = #buf.get_i8();},
-            Int16 => quote!{#val = #buf.get_i16_le();},
-            Int32 => quote!{#val = #buf.get_i32_le();},
-            Int64 => quote!{#val = #buf.get_i64_le();},
-            Float => quote!{#val = #buf.get_f32_le();},
-            Double => quote!{#val = #buf.get_f64_le();},
+            Char => quote! {#val = #buf.get_u8() as char;},
+            UInt8 => quote! {#val = #buf.get_u8();},
+            UInt16 => quote! {#val = #buf.get_u16_le();},
+            UInt32 => quote! {#val = #buf.get_u32_le();},
+            UInt64 => quote! {#val = #buf.get_u64_le();},
+            UInt8MavlinkVersion => quote! {#val = #buf.get_u8();},
+            Int8 => quote! {#val = #buf.get_i8();},
+            Int16 => quote! {#val = #buf.get_i16_le();},
+            Int32 => quote! {#val = #buf.get_i32_le();},
+            Int64 => quote! {#val = #buf.get_i64_le();},
+            Float => quote! {#val = #buf.get_f32_le();},
+            Double => quote! {#val = #buf.get_f64_le();},
             Array(t, size) => {
                 if size > 32 {
                     // it is a vector
                     let r = t.rust_reader(Ident::from("let val"), buf.clone());
-                    quote!{
+                    quote! {
                         for _ in 0..#size {
                             #r
                             #val.push(val);
@@ -674,7 +784,7 @@ impl MavType {
                 } else {
                     // handle as a slice
                     let r = t.rust_reader(Ident::from("let val"), buf.clone());
-                    quote!{
+                    quote! {
                         for idx in 0..#size {
                             #r
                             #val[idx] = val;
@@ -689,26 +799,26 @@ impl MavType {
     pub fn rust_writer(&self, val: Ident, buf: Ident) -> Tokens {
         use self::MavType::*;
         match self.clone() {
-            UInt8MavlinkVersion => quote!{#buf.put_u8(#val);},
-            UInt8 => quote!{#buf.put_u8(#val);},
-            Char => quote!{#buf.put_u8(#val as u8);},
-            UInt16 => quote!{#buf.put_u16_le(#val);},
-            UInt32 => quote!{#buf.put_u32_le(#val);},
-            Int8 => quote!{#buf.put_i8(#val);},
-            Int16 => quote!{#buf.put_i16_le(#val);},
-            Int32 => quote!{#buf.put_i32_le(#val);},
-            Float => quote!{#buf.put_f32_le(#val);},
-            UInt64 => quote!{#buf.put_u64_le(#val);},
-            Int64 => quote!{#buf.put_i64_le(#val);},
-            Double => quote!{#buf.put_f64_le(#val);},
-            Array(t,_size) => {
+            UInt8MavlinkVersion => quote! {#buf.put_u8(#val);},
+            UInt8 => quote! {#buf.put_u8(#val);},
+            Char => quote! {#buf.put_u8(#val as u8);},
+            UInt16 => quote! {#buf.put_u16_le(#val);},
+            UInt32 => quote! {#buf.put_u32_le(#val);},
+            Int8 => quote! {#buf.put_i8(#val);},
+            Int16 => quote! {#buf.put_i16_le(#val);},
+            Int32 => quote! {#buf.put_i32_le(#val);},
+            Float => quote! {#buf.put_f32_le(#val);},
+            UInt64 => quote! {#buf.put_u64_le(#val);},
+            Int64 => quote! {#buf.put_i64_le(#val);},
+            Double => quote! {#buf.put_f64_le(#val);},
+            Array(t, _size) => {
                 let w = t.rust_writer(Ident::from("*val"), buf.clone());
-                quote!{
+                quote! {
                     for val in &#val {
                         #w
                     }
                 }
-            },
+            }
         }
     }
 
@@ -780,7 +890,7 @@ impl MavType {
                     // we can use a slice, as Rust derives lot of thinsg for slices <= 32 elements
                     format!("[{};{}]", t.rust_type(), size)
                 }
-            },
+            }
         }
     }
 
@@ -791,8 +901,6 @@ impl MavType {
     }
 }
 
-
-
 #[derive(Debug, PartialEq, Clone, Copy)]
 #[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
 #[cfg_attr(feature = "serde", serde(tag = "type"))]
@@ -857,7 +965,6 @@ fn is_valid_parent(p: Option<MavXmlElement>, s: MavXmlElement) -> bool {
     }
 }
 
-
 pub fn parse_profile(file: &mut dyn Read) -> MavProfile {
     let mut stack: Vec<MavXmlElement> = vec![];
 
@@ -871,10 +978,12 @@ pub fn parse_profile(file: &mut dyn Read) -> MavProfile {
     let mut message = MavMessage::default();
     let mut mavenum = MavEnum::default();
     let mut entry = MavEnumEntry::default();
+    let mut include = String::new();
     let mut paramid: Option<usize> = None;
 
     let mut xml_filter = MavXmlFilter::default();
-    let mut parser: Vec<Result<XmlEvent, xml::reader::Error>> = EventReader::new(file).into_iter().collect();
+    let mut parser: Vec<Result<XmlEvent, xml::reader::Error>> =
+        EventReader::new(file).into_iter().collect();
     xml_filter.filter(&mut parser);
     for e in parser {
         match e {
@@ -913,6 +1022,9 @@ pub fn parse_profile(file: &mut dyn Read) -> MavProfile {
                     MavXmlElement::Entry => {
                         entry = Default::default();
                     }
+                    MavXmlElement::Include => {
+                        include = Default::default();
+                    }
                     MavXmlElement::Param => {
                         paramid = None;
                     }
@@ -925,18 +1037,18 @@ pub fn parse_profile(file: &mut dyn Read) -> MavProfile {
                     match stack.last() {
                         Some(&MavXmlElement::Enum) => match attr.name.local_name.clone().as_ref() {
                             "name" => {
-                                mavenum.name =
-                                    attr.value
-                                        .clone()
-                                        .split("_")
-                                        .map(|x| x.to_lowercase())
-                                        .map(|x| {
-                                            let mut v: Vec<char> = x.chars().collect();
-                                            v[0] = v[0].to_uppercase().nth(0).unwrap();
-                                            v.into_iter().collect()
-                                        })
-                                        .collect::<Vec<String>>()
-                                        .join("");
+                                mavenum.name = attr
+                                    .value
+                                    .clone()
+                                    .split("_")
+                                    .map(|x| x.to_lowercase())
+                                    .map(|x| {
+                                        let mut v: Vec<char> = x.chars().collect();
+                                        v[0] = v[0].to_uppercase().nth(0).unwrap();
+                                        v.into_iter().collect()
+                                    })
+                                    .collect::<Vec<String>>()
+                                    .join("");
                                 //mavenum.name = attr.value.clone();
                             }
                             _ => (),
@@ -967,18 +1079,18 @@ pub fn parse_profile(file: &mut dyn Read) -> MavProfile {
                             match attr.name.local_name.clone().as_ref() {
                                 "name" => {
                                     /*message.name = attr
-                                        .value
-                                        .clone()
-                                        .split("_")
-                                        .map(|x| x.to_lowercase())
-                                        .map(|x| {
-                                            let mut v: Vec<char> = x.chars().collect();
-                                            v[0] = v[0].to_uppercase().nth(0).unwrap();
-                                            v.into_iter().collect()
-                                        })
-                                        .collect::<Vec<String>>()
-                                        .join("");
-                                        */
+                                    .value
+                                    .clone()
+                                    .split("_")
+                                    .map(|x| x.to_lowercase())
+                                    .map(|x| {
+                                        let mut v: Vec<char> = x.chars().collect();
+                                        v[0] = v[0].to_uppercase().nth(0).unwrap();
+                                        v.into_iter().collect()
+                                    })
+                                    .collect::<Vec<String>>()
+                                    .join("");
+                                    */
                                     message.name = attr.value.clone();
                                 }
                                 "id" => {
@@ -1064,16 +1176,16 @@ pub fn parse_profile(file: &mut dyn Read) -> MavProfile {
                         }
                     }
                     (Some(&Include), Some(&Mavlink)) => {
-                        println!("TODO: include {:?}", s);
+                        include = s.replace("\n", "");
                     }
                     (Some(&Version), Some(&Mavlink)) => {
-                        println!("TODO: version {:?}", s);
+                        eprintln!("TODO: version {:?}", s);
                     }
                     (Some(&Dialect), Some(&Mavlink)) => {
-                        println!("TODO: dialect {:?}", s);
+                        eprintln!("TODO: dialect {:?}", s);
                     }
                     (Some(Deprecated), _) => {
-                        println!("TODO: deprecated {:?}", s);
+                        eprintln!("TODO: deprecated {:?}", s);
                     }
                     data => {
                         panic!("unexpected text data {:?} reading {:?}", data, s);
@@ -1095,13 +1207,16 @@ pub fn parse_profile(file: &mut dyn Read) -> MavProfile {
                     Some(&MavXmlElement::Enum) => {
                         profile.enums.push(mavenum.clone());
                     }
+                    Some(&MavXmlElement::Include) => {
+                        profile.includes.push(include.clone());
+                    }
                     _ => (),
                 }
                 stack.pop();
                 // println!("{}-{}", indent(depth), name);
             }
             Err(e) => {
-                println!("Error: {}", e);
+                eprintln!("Error: {}", e);
                 break;
             }
             _ => {}
@@ -1119,12 +1234,7 @@ pub fn generate<R: Read, W: Write>(input: &mut R, output_rust: &mut W) {
 
     // rust file
     let rust_tokens = profile.emit_rust();
-    //writeln!(output_rust, "{}", rust_tokens).unwrap();
-
-    let rust_src = rust_tokens.into_string();
-    let mut cfg = rustfmt::config::Config::default();
-    cfg.set().write_mode(rustfmt::config::WriteMode::Display);
-    let _ = rustfmt::format_input(rustfmt::Input::Text(rust_src), &cfg, Some(output_rust)).expect("Failed to perform format.");
+    writeln!(output_rust, "{}", rust_tokens).unwrap();
 }
 
 /// CRC operates over names of the message and names of its fields
@@ -1185,20 +1295,23 @@ impl MavXmlFilter {
     }
 
     #[cfg(feature = "emit-extensions")]
-    pub fn filter_extension(&mut self, _element: &Result<xml::reader::XmlEvent, xml::reader::Error>) -> bool {
+    pub fn filter_extension(
+        &mut self,
+        _element: &Result<xml::reader::XmlEvent, xml::reader::Error>,
+    ) -> bool {
         return true;
     }
 
     /// Ignore extension fields
     #[cfg(not(feature = "emit-extensions"))]
-    pub fn filter_extension(&mut self, element: &Result<xml::reader::XmlEvent, xml::reader::Error>) -> bool {
+    pub fn filter_extension(
+        &mut self,
+        element: &Result<xml::reader::XmlEvent, xml::reader::Error>,
+    ) -> bool {
         match element {
             Ok(content) => {
                 match content {
-                    XmlEvent::StartElement{
-                        name,
-                        ..
-                    } => {
+                    XmlEvent::StartElement { name, .. } => {
                         let id = match identify_element(&name.to_string()) {
                             None => {
                                 panic!("unexpected element {:?}", name);
@@ -1208,7 +1321,7 @@ impl MavXmlFilter {
                         match id {
                             MavXmlElement::Extensions => {
                                 self.extension_filter.is_in = true;
-                            },
+                            }
                             _ => {}
                         }
                     }
@@ -1230,7 +1343,7 @@ impl MavXmlFilter {
                     _ => {}
                 }
                 return !self.extension_filter.is_in;
-            },
+            }
             Err(error) => panic!("Failed to filter XML: {}", error),
         }
     }
diff --git a/build/patches/fix-ekf-status-report.patch b/build/patches/fix-ekf-status-report.patch
new file mode 100644
index 0000000000000000000000000000000000000000..b16218443cc311e357d56f5f035dd7a28c06a7f5
--- /dev/null
+++ b/build/patches/fix-ekf-status-report.patch
@@ -0,0 +1,25 @@
+From 418fcf42d4f8b2c682ea7300acff1dbb990d5da6 Mon Sep 17 00:00:00 2001
+From: Ibiyemi Abiodun <ibiyemi@intulon.com>
+Date: Sun, 1 Mar 2020 16:48:13 -0500
+Subject: [PATCH] fix ekf status report message
+
+---
+ message_definitions/v1.0/ardupilotmega.xml | 2 +-
+ 1 file changed, 1 insertion(+), 1 deletion(-)
+
+diff --git a/message_definitions/v1.0/ardupilotmega.xml b/message_definitions/v1.0/ardupilotmega.xml
+index 35c30e44..37f068ea 100644
+--- a/message_definitions/v1.0/ardupilotmega.xml
++++ b/message_definitions/v1.0/ardupilotmega.xml
+@@ -1380,7 +1380,7 @@
+     <!-- EKF status message from autopilot to GCS. -->
+     <message id="193" name="EKF_STATUS_REPORT">
+       <description>EKF Status message including flags and variances.</description>
+-      <field type="uint16_t" name="flags" enum="EKF_STATUS_FLAGS">Flags.</field>
++      <field type="uint16_t" name="flags" enum="EKF_STATUS_FLAGS" display="bitmask">Flags.</field>
+       <!-- supported flags see EKF_STATUS_FLAGS enum -->
+       <field type="float" name="velocity_variance">Velocity variance.</field>
+       <!-- below 0.5 is good, 0.5~0.79 is warning, 0.8 or higher is bad -->
+-- 
+2.25.1
+
diff --git a/build/util.rs b/build/util.rs
new file mode 100644
index 0000000000000000000000000000000000000000..bb8911f6fb1706a0fce658dab1b86615dcfa9073
--- /dev/null
+++ b/build/util.rs
@@ -0,0 +1,11 @@
+use std::path::PathBuf;
+
+pub fn to_module_name<P: Into<PathBuf>>(file_name: P) -> String {
+    file_name
+        .into()
+        .file_stem() // remove extension
+        .unwrap()
+        .to_string_lossy() // convert to string
+        .to_lowercase() // all lowercase
+        .replace(|c: char| !c.is_alphanumeric(), "_") // remove non alphanum
+}
diff --git a/rustfmt.toml b/rustfmt.toml
new file mode 100644
index 0000000000000000000000000000000000000000..c51666e8f4d24175dd874d832718c5e56be8e193
--- /dev/null
+++ b/rustfmt.toml
@@ -0,0 +1 @@
+edition = "2018"
\ No newline at end of file
diff --git a/src/bin/mavlink-dump.rs b/src/bin/mavlink-dump.rs
index d21cee4b747ee8c5e16004024ca5ca4b8e33e103..ce3605aa2c95b05fc090a420ca9ea6f4f8678469 100644
--- a/src/bin/mavlink-dump.rs
+++ b/src/bin/mavlink-dump.rs
@@ -1,14 +1,12 @@
 #[cfg(feature = "std")]
+use std::env;
+#[cfg(feature = "std")]
 use std::sync::Arc;
 #[cfg(feature = "std")]
 use std::thread;
 #[cfg(feature = "std")]
-use std::env;
-#[cfg(feature = "std")]
 use std::time::Duration;
 
-
-
 #[cfg(not(feature = "std"))]
 fn main() {}
 
@@ -24,25 +22,26 @@ fn main() {
     }
 
     let mut mavconn = mavlink::connect(&args[1]).unwrap();
-    // here as an example we force the protocol version to mavlink V1: 
+    // here as an example we force the protocol version to mavlink V1:
     // the default for this library is mavlink V2
     mavconn.set_protocol_version(mavlink::MavlinkVersion::V1);
 
     let vehicle = Arc::new(mavconn);
-    vehicle.send(&mavlink::MavHeader::default(), &request_parameters()).unwrap();
-    vehicle.send(&mavlink::MavHeader::default(), &request_stream()).unwrap();
+    vehicle
+        .send(&mavlink::MavHeader::default(), &request_parameters())
+        .unwrap();
+    vehicle
+        .send(&mavlink::MavHeader::default(), &request_stream())
+        .unwrap();
 
     thread::spawn({
         let vehicle = vehicle.clone();
-        move || {
-            loop {
-                let res = vehicle.send_default(&heartbeat_message());
-                if res.is_ok() {
-                    thread::sleep(Duration::from_secs(1));
-                }
-                else {
-                    println!("send failed: {:?}", res);
-                }
+        move || loop {
+            let res = vehicle.send_default(&heartbeat_message());
+            if res.is_ok() {
+                thread::sleep(Duration::from_secs(1));
+            } else {
+                println!("send failed: {:?}", res);
             }
         }
     });
@@ -51,16 +50,16 @@ fn main() {
         match vehicle.recv() {
             Ok((_header, msg)) => {
                 println!("received: {:?}", msg);
-            },
+            }
             Err(e) => {
                 match e.kind() {
                     std::io::ErrorKind::WouldBlock => {
                         //no messages currently available to receive -- wait a while
                         thread::sleep(Duration::from_secs(1));
                         continue;
-                    },
+                    }
                     _ => {
-                        println ! ("recv error: {:?}", e);
+                        println!("recv error: {:?}", e);
                         break;
                     }
                 }
diff --git a/src/connection/direct_serial.rs b/src/connection/direct_serial.rs
index b4f79de6737837549b424df604ff0ae3ccd4d223..cb026fe4237fabf6b257083c86267064455029ce 100644
--- a/src/connection/direct_serial.rs
+++ b/src/connection/direct_serial.rs
@@ -1,36 +1,30 @@
-
 extern crate serial;
 
-use std::sync::Mutex;
-use std::io::{self};
 use crate::connection::MavConnection;
-use crate::common::MavMessage;
-use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion};
+use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message};
+use std::io::{self};
+use std::sync::Mutex;
 
 //TODO why is this import so hairy?
 use crate::connection::direct_serial::serial::prelude::*;
 
-
 /// Serial MAVLINK connection
 
-
 pub fn open(settings: &str) -> io::Result<SerialConnection> {
     let settings_toks: Vec<&str> = settings.split(":").collect();
     if settings_toks.len() < 2 {
-        return Err(
-            io::Error::new(
-                io::ErrorKind::AddrNotAvailable,
-                "Incomplete port settings",
-            ))
+        return Err(io::Error::new(
+            io::ErrorKind::AddrNotAvailable,
+            "Incomplete port settings",
+        ));
     }
 
     let baud_opt = settings_toks[1].parse::<usize>();
     if baud_opt.is_err() {
-        return Err(
-            io::Error::new(
-                io::ErrorKind::AddrNotAvailable,
-                "Invalid baud rate",
-            ))
+        return Err(io::Error::new(
+            io::ErrorKind::AddrNotAvailable,
+            "Invalid baud rate",
+        ));
     }
 
     let baud = serial::core::BaudRate::from_speed(baud_opt.unwrap());
@@ -44,33 +38,30 @@ pub fn open(settings: &str) -> io::Result<SerialConnection> {
     };
 
     let port_name = settings_toks[0];
-    let mut port  = serial::open(port_name)?;
+    let mut port = serial::open(port_name)?;
     port.configure(&settings)?;
 
     Ok(SerialConnection {
         port: Mutex::new(port),
         sequence: Mutex::new(0),
-        protocol_version: MavlinkVersion::V2
+        protocol_version: MavlinkVersion::V2,
     })
-
 }
 
-
-
 pub struct SerialConnection {
     port: Mutex<serial::SystemPort>,
     sequence: Mutex<u8>,
     protocol_version: MavlinkVersion,
 }
 
-impl MavConnection for SerialConnection {
-    fn recv(&self) -> io::Result<(MavHeader, MavMessage)> {
+impl<M: Message> MavConnection<M> for SerialConnection {
+    fn recv(&self) -> io::Result<(MavHeader, M)> {
         let mut port = self.port.lock().unwrap();
 
         loop {
             match read_versioned_msg(&mut *port, self.protocol_version) {
                 Ok((h, m)) => {
-                    return Ok( (h,m) );
+                    return Ok((h, m));
                 }
                 Err(e) => {
                     //println!("{:?}",e);
@@ -78,14 +69,14 @@ impl MavConnection for SerialConnection {
                         io::ErrorKind::UnexpectedEof => {
                             return Err(e);
                         }
-                        _ => {},
+                        _ => {}
                     }
                 }
             }
         }
     }
 
-    fn send(&self, header: &MavHeader, data: &MavMessage) -> io::Result<()> {
+    fn send(&self, header: &MavHeader, data: &M) -> io::Result<()> {
         let mut port = self.port.lock().unwrap();
         let mut sequence = self.sequence.lock().unwrap();
 
@@ -108,6 +99,4 @@ impl MavConnection for SerialConnection {
     fn get_protocol_version(&self) -> MavlinkVersion {
         self.protocol_version
     }
-
-
 }
diff --git a/src/connection/file.rs b/src/connection/file.rs
index 5b4870e97d7766e28606a75bb4fdc172a5cad6da..98617f8847dc2a945ec4ea894610114c1561a1cd 100644
--- a/src/connection/file.rs
+++ b/src/connection/file.rs
@@ -1,6 +1,5 @@
-use crate::common::MavMessage;
 use crate::connection::MavConnection;
-use crate::{read_versioned_msg, MavHeader, MavlinkVersion};
+use crate::{read_versioned_msg, MavHeader, MavlinkVersion, Message};
 use std::fs::File;
 use std::io::{self};
 use std::sync::Mutex;
@@ -24,8 +23,8 @@ pub struct FileConnection {
     protocol_version: MavlinkVersion,
 }
 
-impl MavConnection for FileConnection {
-    fn recv(&self) -> io::Result<(MavHeader, MavMessage)> {
+impl<M: Message> MavConnection<M> for FileConnection {
+    fn recv(&self) -> io::Result<(MavHeader, M)> {
         let mut file = self.file.lock().unwrap();
 
         loop {
@@ -33,19 +32,17 @@ impl MavConnection for FileConnection {
                 Ok((h, m)) => {
                     return Ok((h, m));
                 }
-                Err(e) => {
-                    match e.kind() {
-                        io::ErrorKind::UnexpectedEof => {
-                            return Err(e);
-                        }
-                        _ => {}
+                Err(e) => match e.kind() {
+                    io::ErrorKind::UnexpectedEof => {
+                        return Err(e);
                     }
-                }
+                    _ => {}
+                },
             }
         }
     }
 
-    fn send(&self, _header: &MavHeader, _data: &MavMessage) -> io::Result<()> {
+    fn send(&self, _header: &MavHeader, _data: &M) -> io::Result<()> {
         Ok(())
     }
 
diff --git a/src/connection/mod.rs b/src/connection/mod.rs
index 738b089217ca2412caccceb9c5f7221d301c48ad..9d39647b5df412c778d2082d662dde8aec93aced 100644
--- a/src/connection/mod.rs
+++ b/src/connection/mod.rs
@@ -1,6 +1,4 @@
-use crate::common::MavMessage;
-use crate::{MavFrame, MavHeader, MavlinkVersion};
-
+use crate::{MavFrame, MavHeader, MavlinkVersion, Message};
 
 use std::io::{self};
 
@@ -16,33 +14,36 @@ mod direct_serial;
 mod file;
 
 /// A MAVLink connection
-pub trait MavConnection {
-
+pub trait MavConnection<M: Message> {
     /// Receive a mavlink message.
     ///
     /// Blocks until a valid frame is received, ignoring invalid messages.
-    fn recv(&self) -> io::Result<(MavHeader,MavMessage)>;
+    fn recv(&self) -> io::Result<(MavHeader, M)>;
 
     /// Send a mavlink message
-    fn send(&self, header: &MavHeader, data: &MavMessage) -> io::Result<()>;
+    fn send(&self, header: &MavHeader, data: &M) -> io::Result<()>;
 
     fn set_protocol_version(&mut self, version: MavlinkVersion);
     fn get_protocol_version(&self) -> MavlinkVersion;
 
     /// Write whole frame
-    fn send_frame(&self, frame: &MavFrame) -> io::Result<()> {
+    fn send_frame(&self, frame: &MavFrame<M>) -> io::Result<()> {
         self.send(&frame.header, &frame.msg)
     }
 
     /// Read whole frame
-    fn recv_frame(&self) -> io::Result<MavFrame> {
-        let (header,msg) = self.recv()?;
+    fn recv_frame(&self) -> io::Result<MavFrame<M>> {
+        let (header, msg) = self.recv()?;
         let protocol_version = self.get_protocol_version();
-        Ok(MavFrame{header,msg,protocol_version})
+        Ok(MavFrame {
+            header,
+            msg,
+            protocol_version,
+        })
     }
 
     /// Send a message with default header
-    fn send_default(&self, data: &MavMessage) -> io::Result<()> {
+    fn send_default(&self, data: &M) -> io::Result<()> {
         let header = MavHeader::default();
         self.send(&header, data)
     }
@@ -61,32 +62,37 @@ pub trait MavConnection {
 ///
 /// The type of the connection is determined at runtime based on the address type, so the
 /// connection is returned as a trait object.
-pub fn connect(address: &str) -> io::Result<Box<dyn MavConnection + Sync + Send>> {
-
+pub fn connect<M: Message>(address: &str) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
     let protocol_err = Err(io::Error::new(
         io::ErrorKind::AddrNotAvailable,
         "Protocol unsupported",
     ));
 
     if cfg!(feature = "tcp") && address.starts_with("tcp") {
-        #[cfg(feature = "tcp")] {
+        #[cfg(feature = "tcp")]
+        {
             tcp::select_protocol(address)
         }
-        #[cfg(not(feature = "tcp"))] {
+        #[cfg(not(feature = "tcp"))]
+        {
             protocol_err
         }
     } else if cfg!(feature = "udp") && address.starts_with("udp") {
-        #[cfg(feature = "udp")] {
+        #[cfg(feature = "udp")]
+        {
             udp::select_protocol(address)
         }
-        #[cfg(not(feature = "udp"))] {
+        #[cfg(not(feature = "udp"))]
+        {
             protocol_err
         }
     } else if cfg!(feature = "direct-serial") && address.starts_with("serial:") {
-        #[cfg(feature = "direct-serial")] {
+        #[cfg(feature = "direct-serial")]
+        {
             Ok(Box::new(direct_serial::open(&address["serial:".len()..])?))
         }
-        #[cfg(not(feature = "direct-serial"))] {
+        #[cfg(not(feature = "direct-serial"))]
+        {
             protocol_err
         }
     } else if address.starts_with("file") {
@@ -95,5 +101,3 @@ pub fn connect(address: &str) -> io::Result<Box<dyn MavConnection + Sync + Send>
         protocol_err
     }
 }
-
-
diff --git a/src/connection/tcp.rs b/src/connection/tcp.rs
index 034f40eab47f056d01a51fa00c5bd323ba1bbbfb..448adbe4d769e4778b0baf4a76b48f27298eb2cc 100644
--- a/src/connection/tcp.rs
+++ b/src/connection/tcp.rs
@@ -1,30 +1,34 @@
-
-
+use crate::connection::MavConnection;
+use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message};
+use std::io::{self};
+use std::net::ToSocketAddrs;
 use std::net::{TcpListener, TcpStream};
-use std::time::Duration;
 use std::sync::Mutex;
-use std::net::{ToSocketAddrs};
-use std::io::{self};
-use crate::connection::MavConnection;
-use crate::common::MavMessage;
-use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion};
+use std::time::Duration;
 
 /// TCP MAVLink connection
 
-
-pub fn select_protocol(address: &str) -> io::Result<Box<dyn MavConnection + Sync + Send>> {
-    if address.starts_with("tcpout:")  {
+pub fn select_protocol<M: Message>(
+    address: &str,
+) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
+    if address.starts_with("tcpout:") {
         Ok(Box::new(tcpout(&address["tcpout:".len()..])?))
     } else if address.starts_with("tcpin:") {
         Ok(Box::new(tcpin(&address["tcpin:".len()..])?))
-    }
-    else {
-        Err(io::Error::new(io::ErrorKind::AddrNotAvailable,"Protocol unsupported"))
+    } else {
+        Err(io::Error::new(
+            io::ErrorKind::AddrNotAvailable,
+            "Protocol unsupported",
+        ))
     }
 }
 
 pub fn tcpout<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
-    let addr = address.to_socket_addrs().unwrap().next().expect("Host address lookup failed.");
+    let addr = address
+        .to_socket_addrs()
+        .unwrap()
+        .next()
+        .expect("Host address lookup failed.");
     let socket = TcpStream::connect(&addr)?;
     socket.set_read_timeout(Some(Duration::from_millis(100)))?;
 
@@ -34,12 +38,16 @@ pub fn tcpout<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
             socket: socket,
             sequence: 0,
         }),
-        protocol_version: MavlinkVersion::V2
+        protocol_version: MavlinkVersion::V2,
     })
 }
 
 pub fn tcpin<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
-    let addr = address.to_socket_addrs().unwrap().next().expect("Invalid address");
+    let addr = address
+        .to_socket_addrs()
+        .unwrap()
+        .next()
+        .expect("Invalid address");
     let listener = TcpListener::bind(&addr)?;
 
     //For now we only accept one incoming stream: this blocks until we get one
@@ -52,13 +60,13 @@ pub fn tcpin<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
                         socket: socket,
                         sequence: 0,
                     }),
-                    protocol_version: MavlinkVersion::V2
+                    protocol_version: MavlinkVersion::V2,
                 })
-            },
+            }
             Err(e) => {
                 //TODO don't println in lib
                 println!("listener err: {}", e);
-            },
+            }
         }
     }
     Err(io::Error::new(
@@ -67,7 +75,6 @@ pub fn tcpin<T: ToSocketAddrs>(address: T) -> io::Result<TcpConnection> {
     ))
 }
 
-
 pub struct TcpConnection {
     reader: Mutex<TcpStream>,
     writer: Mutex<TcpWrite>,
@@ -79,14 +86,13 @@ struct TcpWrite {
     sequence: u8,
 }
 
-
-impl MavConnection for TcpConnection {
-    fn recv(&self) -> io::Result<(MavHeader, MavMessage)> {
+impl<M: Message> MavConnection<M> for TcpConnection {
+    fn recv(&self) -> io::Result<(MavHeader, M)> {
         let mut lock = self.reader.lock().expect("tcp read failure");
         read_versioned_msg(&mut *lock, self.protocol_version)
     }
 
-    fn send(&self, header: &MavHeader, data: &MavMessage) -> io::Result<()> {
+    fn send(&self, header: &MavHeader, data: &M) -> io::Result<()> {
         let mut lock = self.writer.lock().unwrap();
 
         let header = MavHeader {
diff --git a/src/connection/udp.rs b/src/connection/udp.rs
index dad5ea7a3c71f1a25d63b4108368789fe1d76d55..107232a8a8fe3ca01658301567062a9e0be3e5cf 100644
--- a/src/connection/udp.rs
+++ b/src/connection/udp.rs
@@ -1,43 +1,49 @@
-
-
-use std::net::{SocketAddr, UdpSocket};
+use crate::connection::MavConnection;
+use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion, Message};
 use std::io::Read;
+use std::io::{self};
+use std::net::ToSocketAddrs;
+use std::net::{SocketAddr, UdpSocket};
 use std::str::FromStr;
 use std::sync::Mutex;
-use std::net::{ToSocketAddrs};
-use std::io::{self};
-use crate::connection::MavConnection;
-use crate::common::MavMessage;
-use crate::{read_versioned_msg, write_versioned_msg, MavHeader, MavlinkVersion};
 
 /// UDP MAVLink connection
 
-
-pub fn select_protocol(address: &str) -> io::Result<Box<dyn MavConnection + Sync + Send>> {
+pub fn select_protocol<M: Message>(
+    address: &str,
+) -> io::Result<Box<dyn MavConnection<M> + Sync + Send>> {
     if address.starts_with("udpin:") {
         Ok(Box::new(udpin(&address["udpin:".len()..])?))
     } else if address.starts_with("udpout:") {
         Ok(Box::new(udpout(&address["udpout:".len()..])?))
-    }
-    else {
-        Err(io::Error::new(io::ErrorKind::AddrNotAvailable,"Protocol unsupported"))
+    } else {
+        Err(io::Error::new(
+            io::ErrorKind::AddrNotAvailable,
+            "Protocol unsupported",
+        ))
     }
 }
 
 pub fn udpout<T: ToSocketAddrs>(address: T) -> io::Result<UdpConnection> {
-    let addr = address.to_socket_addrs().unwrap().next().expect("Invalid address");
+    let addr = address
+        .to_socket_addrs()
+        .unwrap()
+        .next()
+        .expect("Invalid address");
     let socket = UdpSocket::bind(&SocketAddr::from_str("0.0.0.0:0").unwrap())?;
     UdpConnection::new(socket, false, Some(addr))
 }
 
 pub fn udpin<T: ToSocketAddrs>(address: T) -> io::Result<UdpConnection> {
-    let addr = address.to_socket_addrs().unwrap().next().expect("Invalid address");
+    let addr = address
+        .to_socket_addrs()
+        .unwrap()
+        .next()
+        .expect("Invalid address");
     let socket = UdpSocket::bind(&addr)?;
     UdpConnection::new(socket, true, None)
 }
 
-
-
 struct UdpWrite {
     socket: UdpSocket,
     dest: Option<SocketAddr>,
@@ -113,13 +119,13 @@ impl UdpConnection {
                 dest: dest,
                 sequence: 0,
             }),
-            protocol_version: MavlinkVersion::V2
+            protocol_version: MavlinkVersion::V2,
         })
     }
 }
 
-impl MavConnection for UdpConnection {
-    fn recv(&self) -> io::Result<(MavHeader, MavMessage)> {
+impl<M: Message> MavConnection<M> for UdpConnection {
+    fn recv(&self) -> io::Result<(MavHeader, M)> {
         let mut guard = self.reader.lock().unwrap();
         let state = &mut *guard;
         loop {
@@ -133,12 +139,12 @@ impl MavConnection for UdpConnection {
             }
 
             if let Ok((h, m)) = read_versioned_msg(&mut state.recv_buf, self.protocol_version) {
-                return Ok((h,m));
+                return Ok((h, m));
             }
         }
     }
 
-    fn send(&self, header: &MavHeader, data: &MavMessage) -> io::Result<()> {
+    fn send(&self, header: &MavHeader, data: &M) -> io::Result<()> {
         let mut guard = self.writer.lock().unwrap();
         let state = &mut *guard;
 
@@ -166,4 +172,4 @@ impl MavConnection for UdpConnection {
     fn get_protocol_version(&self) -> MavlinkVersion {
         self.protocol_version
     }
-}
\ No newline at end of file
+}
diff --git a/src/lib.rs b/src/lib.rs
index a1438486164741aefe1b7bb7eae479e9155ece3b..ba87612d33253015081e31f4400be3cc34550134 100644
--- a/src/lib.rs
+++ b/src/lib.rs
@@ -1,16 +1,32 @@
-//! The MAVLink common message set
+//! The MAVLink message set.
 //!
-//! TODO: a parser for no_std environments
+//! # Message sets and the `Message` trait
+//! Each message set has its own module with corresponding data types, including a `MavMessage` enum
+//! that represents all possible messages in that message set. The [`Message`] trait is used to
+//! represent messages in an abstract way, and each `MavMessage` enum implements this trait (for
+//! example, [`ardupilotmega::MavMessage`]). This is then monomorphized to the specific message
+//! set you are using in your application at compile-time via type parameters. If you expect
+//! ArduPilotMega-flavored messages, then you will need a `MavConnection<ardupilotmega::MavMessage>`
+//! and you will receive `ardupilotmega::MavMessage`s from it.
+//!
+//! Some message sets include others. For example, all message sets except `common` include the
+//! common message set. This is represented with extra values in the `MavMessage` enum: a message
+//! in the common message set received on an ArduPilotMega connection will be an
+//! `ardupilotmega::MavMessage::common(common::MavMessage)`.
+//!
+//! Please note that if you want to enable a given message set, you must also enable the
+//! feature for the message sets that it includes. For example, you cannot use the `ardupilotmega`
+//! feature without also using the `uavionix` and `icarous` features.
+//!
+// TODO: a parser for no_std environments
 #![cfg_attr(not(feature = "std"), feature(alloc))]
 #![cfg_attr(not(feature = "std"), no_std)]
 #[cfg(not(feature = "std"))]
 extern crate alloc;
 
-
 #[cfg(feature = "std")]
 use std::io::{Read, Result, Write};
 
-
 #[cfg(feature = "std")]
 extern crate byteorder;
 #[cfg(feature = "std")]
@@ -22,27 +38,28 @@ mod connection;
 pub use self::connection::{connect, MavConnection};
 
 #[cfg(feature = "serde")]
-use serde::{Serialize, Deserialize};
+use serde::{Deserialize, Serialize};
 
 extern crate bytes;
 use bytes::{Buf, Bytes, IntoBuf};
 
-extern crate num_traits;
-extern crate num_derive;
 extern crate bitflags;
-#[macro_use]
-
-#[allow(non_camel_case_types)]
-#[allow(non_snake_case)]
-#[allow(unused_variables)]
-#[allow(unused_mut)]
-pub mod common {
-    use crate::MavlinkVersion; //TODO verify
-    include!(concat!(env!("OUT_DIR"), "/common.rs"));
-}
+extern crate num_derive;
+extern crate num_traits;
 
-/// Encapsulation of all possible Mavlink messages defined in common.xml
-pub use self::common::MavMessage as MavMessage;
+// include generate definitions
+include!(concat!(env!("OUT_DIR"), "/mod.rs"));
+
+pub trait Message
+where
+    Self: Sized,
+{
+    fn message_id(&self) -> u32;
+    fn message_id_from_name(name: &str) -> std::result::Result<u32, &'static str>;
+    fn ser(&self) -> Vec<u8>;
+    fn extra_crc(id: u32) -> u8;
+    fn parse(version: MavlinkVersion, msgid: u32, payload: &[u8]) -> Option<Self>;
+}
 
 /// Metadata from a MAVLink packet header
 #[derive(Debug, Copy, Clone, PartialEq, Eq)]
@@ -85,20 +102,20 @@ impl Default for MavHeader {
 /// and component id
 #[derive(Debug, Clone)]
 #[cfg_attr(feature = "serde", derive(Serialize))]
-pub struct MavFrame {
+pub struct MavFrame<M: Message> {
     pub header: MavHeader,
-    pub msg: MavMessage,
+    pub msg: M,
     pub protocol_version: MavlinkVersion,
 }
 
-impl MavFrame {
+impl<M: Message> MavFrame<M> {
     /// Create a new frame with given message
-//    pub fn new(msg: MavMessage) -> MavFrame {
-//        MavFrame {
-//            header: MavHeader::default(),
-//            msg
-//        }
-//    }
+    //    pub fn new(msg: MavMessage) -> MavFrame {
+    //        MavFrame {
+    //            header: MavHeader::get_default_header(),
+    //            msg
+    //        }
+    //    }
 
     /// Serialize MavFrame into a vector, so it can be sent over a socket, for example.
     pub fn ser(&self) -> Vec<u8> {
@@ -114,7 +131,7 @@ impl MavFrame {
             MavlinkVersion::V2 => {
                 let bytes: [u8; 4] = self.msg.message_id().to_le_bytes();
                 v.extend_from_slice(&bytes);
-            },
+            }
             MavlinkVersion::V1 => {
                 v.push(self.msg.message_id() as u8); //TODO check
             }
@@ -133,20 +150,23 @@ impl MavFrame {
         let system_id = buf.get_u8();
         let component_id = buf.get_u8();
         let sequence = buf.get_u8();
-        let header = MavHeader{system_id,component_id,sequence};
-
-        let msg_id =  match version {
-            MavlinkVersion::V2 => {
-                buf.get_u32_le()
-            },
-            MavlinkVersion::V1 => {
-                buf.get_u8() as u32
-            }
+        let header = MavHeader {
+            system_id,
+            component_id,
+            sequence,
         };
 
+        let msg_id = match version {
+            MavlinkVersion::V2 => buf.get_u32_le(),
+            MavlinkVersion::V1 => buf.get_u8() as u32,
+        };
 
-        if let Some(msg) = MavMessage::parse(version, msg_id, &buf.collect::<Vec<u8>>()) {
-            Some(MavFrame {header, msg, protocol_version: version })
+        if let Some(msg) = M::parse(version, msg_id, &buf.collect::<Vec<u8>>()) {
+            Some(MavFrame {
+                header,
+                msg,
+                protocol_version: version,
+            })
         } else {
             None
         }
@@ -158,19 +178,18 @@ impl MavFrame {
     }
 }
 
-pub fn read_versioned_msg<R: Read>(r: &mut R, version: MavlinkVersion) -> Result<(MavHeader, MavMessage)> {
+pub fn read_versioned_msg<M: Message, R: Read>(
+    r: &mut R,
+    version: MavlinkVersion,
+) -> Result<(MavHeader, M)> {
     match version {
-        MavlinkVersion::V2 => {
-            read_v2_msg(r)
-        },
-        MavlinkVersion::V1 => {
-            read_v1_msg(r)
-        }
+        MavlinkVersion::V2 => read_v2_msg(r),
+        MavlinkVersion::V1 => read_v1_msg(r),
     }
 }
 
 /// Read a MAVLink v1  message from a Read stream.
-pub fn read_v1_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
+pub fn read_v1_msg<M: Message, R: Read>(r: &mut R) -> Result<(MavHeader, M)> {
     loop {
         if r.read_u8()? != MAV_STX {
             continue;
@@ -191,7 +210,7 @@ pub fn read_v1_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
         let mut crc_calc = crc16::State::<crc16::MCRF4XX>::new();
         crc_calc.update(&[len as u8, seq, sysid, compid, msgid]);
         crc_calc.update(payload);
-        crc_calc.update(&[MavMessage::extra_crc(msgid.into() )]);
+        crc_calc.update(&[M::extra_crc(msgid.into())]);
         let recvd_crc = crc_calc.get();
         if recvd_crc != crc {
             // bad crc: ignore message
@@ -199,7 +218,7 @@ pub fn read_v1_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
             continue;
         }
 
-        if let Some(msg) = MavMessage::parse(MavlinkVersion::V1, msgid.into(), payload) {
+        if let Some(msg) = M::parse(MavlinkVersion::V1, msgid.into(), payload) {
             return Ok((
                 MavHeader {
                     sequence: seq,
@@ -215,42 +234,49 @@ pub fn read_v1_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
 const MAVLINK_IFLAG_SIGNED: u8 = 0x01;
 
 /// Read a MAVLink v2  message from a Read stream.
-pub fn read_v2_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
+pub fn read_v2_msg<M: Message, R: Read>(r: &mut R) -> Result<(MavHeader, M)> {
     loop {
         // search for the magic framing value indicating start of mavlink message
         if r.read_u8()? != MAV_STX_V2 {
             continue;
         }
 
-//        println!("Got STX2");
+        //        println!("Got STX2");
         let payload_len = r.read_u8()? as usize;
-//        println!("Got payload_len: {}", payload_len);
+        //        println!("Got payload_len: {}", payload_len);
         let incompat_flags = r.read_u8()?;
-//        println!("Got incompat flags: {}", incompat_flags);
+        //        println!("Got incompat flags: {}", incompat_flags);
         let compat_flags = r.read_u8()?;
-//        println!("Got compat flags: {}", compat_flags);
+        //        println!("Got compat flags: {}", compat_flags);
 
         let seq = r.read_u8()?;
-//        println!("Got seq: {}", seq);
+        //        println!("Got seq: {}", seq);
 
         let sysid = r.read_u8()?;
-//        println!("Got sysid: {}", sysid);
+        //        println!("Got sysid: {}", sysid);
 
         let compid = r.read_u8()?;
-//        println!("Got compid: {}", compid);
+        //        println!("Got compid: {}", compid);
 
-        let mut msgid_buf = [0;4];
+        let mut msgid_buf = [0; 4];
         msgid_buf[0] = r.read_u8()?;
         msgid_buf[1] = r.read_u8()?;
         msgid_buf[2] = r.read_u8()?;
 
-        let header_buf = &[payload_len as u8,
-            incompat_flags, compat_flags,
-            seq, sysid, compid,
-            msgid_buf[0],msgid_buf[1],msgid_buf[2]];
+        let header_buf = &[
+            payload_len as u8,
+            incompat_flags,
+            compat_flags,
+            seq,
+            sysid,
+            compid,
+            msgid_buf[0],
+            msgid_buf[1],
+            msgid_buf[2],
+        ];
 
         let msgid: u32 = u32::from_le_bytes(msgid_buf);
-//        println!("Got msgid: {}", msgid);
+        //        println!("Got msgid: {}", msgid);
 
         //provide a buffer that is the maximum payload size
         let mut payload_buf = [0; 255];
@@ -261,14 +287,14 @@ pub fn read_v2_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
         let crc = r.read_u16::<LittleEndian>()?;
 
         if (incompat_flags & 0x01) == MAVLINK_IFLAG_SIGNED {
-            let mut sign = [0;13];
+            let mut sign = [0; 13];
             r.read_exact(&mut sign)?;
         }
 
         let mut crc_calc = crc16::State::<crc16::MCRF4XX>::new();
         crc_calc.update(header_buf);
         crc_calc.update(payload);
-        let extra_crc = MavMessage::extra_crc(msgid);
+        let extra_crc = M::extra_crc(msgid);
 
         crc_calc.update(&[extra_crc]);
         let recvd_crc = crc_calc.get();
@@ -278,7 +304,7 @@ pub fn read_v2_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
             continue;
         }
 
-        if let Some(msg) = MavMessage::parse(MavlinkVersion::V2, msgid, payload) {
+        if let Some(msg) = M::parse(MavlinkVersion::V2, msgid, payload) {
             return Ok((
                 MavHeader {
                     sequence: seq,
@@ -287,34 +313,33 @@ pub fn read_v2_msg<R: Read>(r: &mut R) -> Result<(MavHeader, MavMessage)> {
                 },
                 msg,
             ));
-        }
-        else {
-            return Err(
-                std::io::Error::new( std::io::ErrorKind::InvalidData, "Invalid MavMessage")
-            );
+        } else {
+            return Err(std::io::Error::new(
+                std::io::ErrorKind::InvalidData,
+                "Invalid MavMessage",
+            ));
         }
     }
 }
 
-
 /// Write a message using the given mavlink version
-pub fn write_versioned_msg<W: Write>(w: &mut W,  version: MavlinkVersion,
-                                     header: MavHeader, data: &MavMessage) -> Result<()> {
+pub fn write_versioned_msg<M: Message, W: Write>(
+    w: &mut W,
+    version: MavlinkVersion,
+    header: MavHeader,
+    data: &M,
+) -> Result<()> {
     match version {
-        MavlinkVersion::V2 => {
-            write_v2_msg(w, header, data)
-        },
-        MavlinkVersion::V1 => {
-            write_v1_msg(w, header, data)
-        }
+        MavlinkVersion::V2 => write_v2_msg(w, header, data),
+        MavlinkVersion::V1 => write_v1_msg(w, header, data),
     }
 }
 
 /// Write a MAVLink v2 message to a Write stream.
-pub fn write_v2_msg<W: Write>(w: &mut W, header: MavHeader, data: &MavMessage) -> Result<()> {
+pub fn write_v2_msg<M: Message, W: Write>(w: &mut W, header: MavHeader, data: &M) -> Result<()> {
     let msgid = data.message_id();
     let payload = data.ser();
-//    println!("write payload_len : {}", payload.len());
+    //    println!("write payload_len : {}", payload.len());
 
     let header = &[
         MAV_STX_V2,
@@ -325,20 +350,20 @@ pub fn write_v2_msg<W: Write>(w: &mut W, header: MavHeader, data: &MavMessage) -
         header.system_id,
         header.component_id,
         (msgid & 0x0000FF) as u8,
-        ((msgid & 0x00FF00) >> 8) as u8 ,
+        ((msgid & 0x00FF00) >> 8) as u8,
         ((msgid & 0xFF0000) >> 16) as u8,
     ];
 
-//    println!("write H: {:?}",header );
+    //    println!("write H: {:?}",header );
 
     let mut crc = crc16::State::<crc16::MCRF4XX>::new();
     crc.update(&header[1..]);
-//    let header_crc = crc.get();
+    //    let header_crc = crc.get();
     crc.update(&payload[..]);
-//    let base_crc = crc.get();
-    let extra_crc = MavMessage::extra_crc(msgid);
-//    println!("write header_crc: {} base_crc: {} extra_crc: {}",
-//             header_crc, base_crc, extra_crc);
+    //    let base_crc = crc.get();
+    let extra_crc = M::extra_crc(msgid);
+    //    println!("write header_crc: {} base_crc: {} extra_crc: {}",
+    //             header_crc, base_crc, extra_crc);
     crc.update(&[extra_crc]);
 
     w.write_all(header)?;
@@ -349,7 +374,7 @@ pub fn write_v2_msg<W: Write>(w: &mut W, header: MavHeader, data: &MavMessage) -
 }
 
 /// Write a MAVLink v1 message to a Write stream.
-pub fn write_v1_msg<W: Write>(w: &mut W, header: MavHeader, data: &MavMessage) -> Result<()> {
+pub fn write_v1_msg<M: Message, W: Write>(w: &mut W, header: MavHeader, data: &M) -> Result<()> {
     let msgid = data.message_id();
     let payload = data.ser();
 
@@ -365,7 +390,7 @@ pub fn write_v1_msg<W: Write>(w: &mut W, header: MavHeader, data: &MavMessage) -
     let mut crc = crc16::State::<crc16::MCRF4XX>::new();
     crc.update(&header[1..]);
     crc.update(&payload[..]);
-    crc.update(&[MavMessage::extra_crc(msgid)]);
+    crc.update(&[M::extra_crc(msgid)]);
 
     w.write_all(header)?;
     w.write_all(&payload[..])?;
@@ -373,10 +398,3 @@ pub fn write_v1_msg<W: Write>(w: &mut W, header: MavHeader, data: &MavMessage) -
 
     Ok(())
 }
-
-
-
-
-
-
-
diff --git a/tests/direct_serial_tests.rs b/tests/direct_serial_tests.rs
index 5b51ae73fda27f1c0644926d1f868973a3dc647c..98aa6175081b4facc1e2ac6fde2b7cd746674b1a 100644
--- a/tests/direct_serial_tests.rs
+++ b/tests/direct_serial_tests.rs
@@ -1,24 +1,26 @@
 extern crate mavlink;
 
 #[cfg(test)]
-#[cfg(all(feature = "std", feature = "direct-serial"))]
+#[cfg(all(feature = "std", feature = "direct-serial", feature = "common"))]
 mod test_direct_serial {
+    use mavlink::common::MavMessage;
+
     #[test]
     pub fn test_incomplete_address() {
-        let conn_result = mavlink::connect("serial:");
+        let conn_result = mavlink::connect::<MavMessage>("serial:");
         assert!(conn_result.is_err(), "Incomplete address should error");
     }
 
     #[test]
     pub fn test_bogus_baud() {
-        let conn_result = mavlink::connect("serial:port1:badbaud");
+        let conn_result = mavlink::connect::<MavMessage>("serial:port1:badbaud");
         assert!(conn_result.is_err(), "Invalid baud should error");
     }
 
     #[test]
     pub fn test_nonexistent_port() {
         let bogus_port_str = "serial:8d73ba8c-eb87-4105-8d0c-2931940e13be:57600";
-        let conn_result = mavlink::connect(bogus_port_str);
+        let conn_result = mavlink::connect::<MavMessage>(bogus_port_str);
         assert!(conn_result.is_err(), "Invalid port should error");
     }
-}
\ No newline at end of file
+}
diff --git a/tests/encode_decode_tests.rs b/tests/encode_decode_tests.rs
index aefb73e4a828f082a5e351428f108e6944f26e99..81adb2228634e5c90099d31d754acf6ee26a025d 100644
--- a/tests/encode_decode_tests.rs
+++ b/tests/encode_decode_tests.rs
@@ -1,11 +1,11 @@
-
 extern crate mavlink;
 
 mod test_shared;
 
-
 #[cfg(test)]
+#[cfg(feature = "common")]
 mod test_encode_decode {
+    use mavlink::{common, Message};
 
     #[test]
     pub fn test_echo_heartbeat() {
@@ -15,11 +15,13 @@ mod test_encode_decode {
         mavlink::write_v2_msg(
             &mut v,
             crate::test_shared::COMMON_MSG_HEADER,
-            &mavlink::common::MavMessage::HEARTBEAT(send_msg.clone()),
-        ).expect("Failed to write message");
+            &common::MavMessage::HEARTBEAT(send_msg.clone()),
+        )
+        .expect("Failed to write message");
 
         let mut c = v.as_slice();
-        let (_header, recv_msg) = mavlink::read_v2_msg(&mut c).expect("Failed to read");
+        let (_header, recv_msg): (mavlink::MavHeader, common::MavMessage) =
+            mavlink::read_v2_msg(&mut c).expect("Failed to read");
         assert_eq!(recv_msg.message_id(), 0);
     }
 
@@ -32,13 +34,14 @@ mod test_encode_decode {
             &mut v,
             crate::test_shared::COMMON_MSG_HEADER,
             &mavlink::common::MavMessage::COMMAND_INT(send_msg.clone()),
-        ).expect("Failed to write message");
+        )
+        .expect("Failed to write message");
 
         let mut c = v.as_slice();
         let (_header, recv_msg) = mavlink::read_v2_msg(&mut c).expect("Failed to read");
 
-        if let mavlink::common::MavMessage::COMMAND_INT(recv_msg) = recv_msg {
-            assert_eq!(recv_msg.command, mavlink::common::MavCmd::MAV_CMD_NAV_TAKEOFF);
+        if let common::MavMessage::COMMAND_INT(recv_msg) = recv_msg {
+            assert_eq!(recv_msg.command, common::MavCmd::MAV_CMD_NAV_TAKEOFF);
         } else {
             panic!("Decoded wrong message type")
         }
@@ -53,16 +56,107 @@ mod test_encode_decode {
             &mut v,
             crate::test_shared::COMMON_MSG_HEADER,
             &mavlink::common::MavMessage::HIL_ACTUATOR_CONTROLS(send_msg.clone()),
-        ).expect("Failed to write message");
+        )
+        .expect("Failed to write message");
 
         let mut c = v.as_slice();
         let (_header, recv_msg) = mavlink::read_v2_msg(&mut c).expect("Failed to read");
         if let mavlink::common::MavMessage::HIL_ACTUATOR_CONTROLS(recv_msg) = recv_msg {
-            assert_eq!(mavlink::common::MavModeFlag::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
-            recv_msg.mode & mavlink::common::MavModeFlag::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED);
+            assert_eq!(
+                mavlink::common::MavModeFlag::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
+                recv_msg.mode & mavlink::common::MavModeFlag::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED
+            );
+        } else {
+            panic!("Decoded wrong message type")
+        }
+    }
+
+    /// This test makes sure that we can still receive messages in the common set
+    /// properly when we're trying to decode APM messages.
+    #[test]
+    #[cfg(all(feature = "ardupilotmega", feature = "uavionix", feature = "icarous"))]
+    pub fn test_echo_apm_heartbeat() {
+        use mavlink::ardupilotmega;
+
+        let mut v = vec![];
+        let send_msg = crate::test_shared::get_heartbeat_msg();
+
+        mavlink::write_v2_msg(
+            &mut v,
+            crate::test_shared::COMMON_MSG_HEADER,
+            &ardupilotmega::MavMessage::common(common::MavMessage::HEARTBEAT(send_msg.clone())),
+        )
+        .expect("Failed to write message");
+
+        let mut c = v.as_slice();
+        let (_header, recv_msg) = mavlink::read_v2_msg(&mut c).expect("Failed to read");
+
+        if let ardupilotmega::MavMessage::common(recv_msg) = recv_msg {
+            match &recv_msg {
+                common::MavMessage::HEARTBEAT(data) => {
+                    assert_eq!(recv_msg.message_id(), 0);
+                }
+                _ => panic!("Decoded wrong message type"),
+            }
         } else {
             panic!("Decoded wrong message type")
         }
     }
 
-}
\ No newline at end of file
+    /// This test makes sure that messages that are not
+    /// in the common set also get encoded and decoded
+    /// properly.
+    #[test]
+    #[cfg(all(feature = "ardupilotmega", feature = "uavionix", feature = "icarous"))]
+    pub fn test_echo_apm_mount_status() {
+        use mavlink::ardupilotmega;
+
+        let mut v = vec![];
+        let send_msg = crate::test_shared::get_apm_mount_status();
+
+        mavlink::write_v2_msg(
+            &mut v,
+            crate::test_shared::COMMON_MSG_HEADER,
+            &ardupilotmega::MavMessage::MOUNT_STATUS(send_msg.clone()),
+        )
+        .expect("Failed to write message");
+
+        let mut c = v.as_slice();
+        let (_header, recv_msg) = mavlink::read_v2_msg(&mut c).expect("Failed to read");
+        if let ardupilotmega::MavMessage::MOUNT_STATUS(recv_msg) = recv_msg {
+            assert_eq!(4, recv_msg.pointing_b);
+        } else {
+            panic!("Decoded wrong message type")
+        }
+    }
+
+    #[test]
+    #[cfg(all(feature = "ardupilotmega", feature = "uavionix", feature = "icarous"))]
+    pub fn test_echo_apm_command_int() {
+        use mavlink::ardupilotmega;
+
+        let mut v = vec![];
+        let send_msg = crate::test_shared::get_cmd_nav_takeoff_msg();
+
+        mavlink::write_v2_msg(
+            &mut v,
+            crate::test_shared::COMMON_MSG_HEADER,
+            &ardupilotmega::MavMessage::common(common::MavMessage::COMMAND_INT(send_msg.clone())),
+        )
+        .expect("Failed to write message");
+
+        let mut c = v.as_slice();
+        let (_header, recv_msg) = mavlink::read_v2_msg(&mut c).expect("Failed to read");
+
+        if let ardupilotmega::MavMessage::common(recv_msg) = recv_msg {
+            match &recv_msg {
+                common::MavMessage::COMMAND_INT(data) => {
+                    assert_eq!(data.command, common::MavCmd::MAV_CMD_NAV_TAKEOFF);
+                }
+                _ => panic!("Decoded wrong message type"),
+            }
+        } else {
+            panic!("Decoded wrong message type")
+        }
+    }
+}
diff --git a/tests/tcp_loopback_tests.rs b/tests/tcp_loopback_tests.rs
index 85d6cf774630c421385f11274c9b416814a0cfc0..f002caeefa46e50b438e0e1535b4e85528656a55 100644
--- a/tests/tcp_loopback_tests.rs
+++ b/tests/tcp_loopback_tests.rs
@@ -3,7 +3,7 @@ extern crate mavlink;
 mod test_shared;
 
 #[cfg(test)]
-#[cfg(all(feature = "std", feature = "tcp"))]
+#[cfg(all(feature = "std", feature = "tcp", feature = "common"))]
 mod test_tcp_connections {
     use std::thread;
 
@@ -12,11 +12,11 @@ mod test_tcp_connections {
     pub fn test_tcp_loopback() {
         const RECEIVE_CHECK_COUNT: i32 = 5;
 
-        let server_thread = thread::spawn( {
+        let server_thread = thread::spawn({
             move || {
                 //TODO consider using get_available_port to use a random port
-                let server = mavlink::connect("tcpin:0.0.0.0:14550")
-                    .expect("Couldn't create server");
+                let server =
+                    mavlink::connect("tcpin:0.0.0.0:14550").expect("Couldn't create server");
 
                 let mut recv_count = 0;
                 for _i in 0..RECEIVE_CHECK_COUNT {
@@ -45,9 +45,10 @@ mod test_tcp_connections {
         // have the client send a few hearbeats
         thread::spawn({
             move || {
-                let msg = mavlink::common::MavMessage::HEARTBEAT( crate::test_shared::get_heartbeat_msg() );
-                let client = mavlink::connect("tcpout:127.0.0.1:14550")
-                    .expect("Couldn't create client");
+                let msg =
+                    mavlink::common::MavMessage::HEARTBEAT(crate::test_shared::get_heartbeat_msg());
+                let client =
+                    mavlink::connect("tcpout:127.0.0.1:14550").expect("Couldn't create client");
                 for _i in 0..RECEIVE_CHECK_COUNT {
                     client.send_default(&msg).ok();
                 }
@@ -56,5 +57,4 @@ mod test_tcp_connections {
 
         server_thread.join().unwrap();
     }
-
-}
\ No newline at end of file
+}
diff --git a/tests/test_shared/mod.rs b/tests/test_shared/mod.rs
index 9bd8322c23520c0c61e066ef5afdcc91540519df..b8fd5dc90c9686d145a04b06a40820f6fd60f479 100644
--- a/tests/test_shared/mod.rs
+++ b/tests/test_shared/mod.rs
@@ -1,13 +1,12 @@
-
 extern crate mavlink;
 
-
 pub const COMMON_MSG_HEADER: mavlink::MavHeader = mavlink::MavHeader {
     sequence: 239,
     system_id: 1,
     component_id: 1,
 };
 
+#[cfg(feature = "common")]
 pub fn get_heartbeat_msg() -> mavlink::common::HEARTBEAT_DATA {
     mavlink::common::HEARTBEAT_DATA {
         custom_mode: 5,
@@ -22,6 +21,7 @@ pub fn get_heartbeat_msg() -> mavlink::common::HEARTBEAT_DATA {
     }
 }
 
+#[cfg(feature = "common")]
 pub fn get_cmd_nav_takeoff_msg() -> mavlink::common::COMMAND_INT_DATA {
     mavlink::common::COMMAND_INT_DATA {
         param1: 1.0,
@@ -36,19 +36,31 @@ pub fn get_cmd_nav_takeoff_msg() -> mavlink::common::COMMAND_INT_DATA {
         target_component: 84,
         frame: mavlink::common::MavFrame::MAV_FRAME_GLOBAL,
         current: 73,
-        autocontinue: 17
+        autocontinue: 17,
     }
 }
 
+#[cfg(feature = "common")]
 pub fn get_hil_actuator_controls_msg() -> mavlink::common::HIL_ACTUATOR_CONTROLS_DATA {
     mavlink::common::HIL_ACTUATOR_CONTROLS_DATA {
         time_usec: 1234567 as u64,
         flags: 0 as u64,
-        controls: [0.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0,
-            10.0, 11.0, 12.0, 13.0, 14.0, 15.0],
+        controls: [
+            0.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0, 13.0, 14.0, 15.0,
+        ],
         mode: mavlink::common::MavModeFlag::MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
             | mavlink::common::MavModeFlag::MAV_MODE_FLAG_STABILIZE_ENABLED
             | mavlink::common::MavModeFlag::MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
     }
 }
 
+#[cfg(all(feature = "ardupilotmega", feature = "uavionix", feature = "icarous"))]
+pub fn get_apm_mount_status() -> mavlink::ardupilotmega::MOUNT_STATUS_DATA {
+    mavlink::ardupilotmega::MOUNT_STATUS_DATA {
+        pointing_a: 3,
+        pointing_b: 4,
+        pointing_c: 5,
+        target_system: 2,
+        target_component: 3,
+    }
+}
diff --git a/tests/udp_loopback_tests.rs b/tests/udp_loopback_tests.rs
index 7df18ad776c5d855c13a182e4e5403d3e7bc4e3d..0d1b191cfafca05ba0301f790edd9907626a9a04 100644
--- a/tests/udp_loopback_tests.rs
+++ b/tests/udp_loopback_tests.rs
@@ -3,25 +3,24 @@ extern crate mavlink;
 mod test_shared;
 
 #[cfg(test)]
-#[cfg(all(feature = "std", feature = "udp"))]
+#[cfg(all(feature = "std", feature = "udp", feature = "common"))]
 mod test_udp_connections {
     use std::thread;
 
-
     /// Test whether we can send a message via UDP and receive it OK
     #[test]
     pub fn test_udp_loopback() {
         const RECEIVE_CHECK_COUNT: i32 = 3;
 
-        let server = mavlink::connect("udpin:0.0.0.0:14551")
-            .expect("Couldn't create server");
+        let server = mavlink::connect("udpin:0.0.0.0:14551").expect("Couldn't create server");
 
         // have the client send one heartbeat per second
         thread::spawn({
             move || {
-                let msg = mavlink::common::MavMessage::HEARTBEAT( crate::test_shared::get_heartbeat_msg() );
-                let client = mavlink::connect("udpout:127.0.0.1:14551")
-                    .expect("Couldn't create client");
+                let msg =
+                    mavlink::common::MavMessage::HEARTBEAT(crate::test_shared::get_heartbeat_msg());
+                let client =
+                    mavlink::connect("udpout:127.0.0.1:14551").expect("Couldn't create client");
                 loop {
                     client.send_default(&msg).ok();
                 }
@@ -50,7 +49,5 @@ mod test_udp_connections {
             }
         }
         assert_eq!(recv_count, RECEIVE_CHECK_COUNT);
-
     }
-
-}
\ No newline at end of file
+}
diff --git a/tests/v1_encode_decode_tests.rs b/tests/v1_encode_decode_tests.rs
index db26f8fe215c8a456ebc2da1d39b4fd433b6138c..d4c96b9e96eb4d8d659f951e252804c870db00e0 100644
--- a/tests/v1_encode_decode_tests.rs
+++ b/tests/v1_encode_decode_tests.rs
@@ -1,16 +1,29 @@
-
 extern crate mavlink;
 
-mod test_shared;
-
+pub mod test_shared;
 
 #[cfg(test)]
-#[cfg(all(feature = "std"))]
+#[cfg(all(feature = "std", feature = "common"))]
 mod test_v1_encode_decode {
 
     pub const HEARTBEAT_V1: &'static [u8] = &[
-        mavlink::MAV_STX, 0x09, 0xef, 0x01, 0x01, 0x00, 0x05, 0x00, 0x00, 0x00, 0x02, 0x03, 0x59, 0x03, 0x03,
-        0xf1, 0xd7,
+        mavlink::MAV_STX,
+        0x09,
+        0xef,
+        0x01,
+        0x01,
+        0x00,
+        0x05,
+        0x00,
+        0x00,
+        0x00,
+        0x02,
+        0x03,
+        0x59,
+        0x03,
+        0x03,
+        0xf1,
+        0xd7,
     ];
 
     #[test]
@@ -43,9 +56,8 @@ mod test_v1_encode_decode {
             crate::test_shared::COMMON_MSG_HEADER,
             &mavlink::common::MavMessage::HEARTBEAT(heartbeat_msg.clone()),
         )
-            .expect("Failed to write message");
+        .expect("Failed to write message");
 
         assert_eq!(&v[..], HEARTBEAT_V1);
     }
-
-}
\ No newline at end of file
+}
diff --git a/tests/v2_encode_decode_tests.rs b/tests/v2_encode_decode_tests.rs
index fabc5fe38c0bad27be46c747e149162f15a3ba71..e2f53c680ac0dcd1851d267d22010891450867a9 100644
--- a/tests/v2_encode_decode_tests.rs
+++ b/tests/v2_encode_decode_tests.rs
@@ -1,24 +1,32 @@
-
 extern crate mavlink;
 
 mod test_shared;
 
-
 #[cfg(test)]
-#[cfg(all(feature = "std"))]
+#[cfg(all(feature = "std", feature = "common"))]
 mod test_v2_encode_decode {
-
     pub const HEARTBEAT_V2: &'static [u8] = &[
         mavlink::MAV_STX_V2, //magic
-        0x09, //payload len
-        0, //incompat flags
-        0, //compat flags
-        0xef, //seq 239
-        0x01, //sys ID
-        0x01, //comp ID
-        0x00, 0x00, 0x00, //msg ID
-        0x05, 0x00, 0x00, 0x00, 0x02, 0x03, 0x59, 0x03, 0x03, //payload
-        16, 240, //checksum
+        0x09,                //payload len
+        0,                   //incompat flags
+        0,                   //compat flags
+        0xef,                //seq 239
+        0x01,                //sys ID
+        0x01,                //comp ID
+        0x00,
+        0x00,
+        0x00, //msg ID
+        0x05,
+        0x00,
+        0x00,
+        0x00,
+        0x02,
+        0x03,
+        0x59,
+        0x03,
+        0x03, //payload
+        16,
+        240, //checksum
     ];
 
     #[test]
@@ -50,31 +58,72 @@ mod test_v2_encode_decode {
             crate::test_shared::COMMON_MSG_HEADER,
             &mavlink::common::MavMessage::HEARTBEAT(heartbeat_msg.clone()),
         )
-            .expect("Failed to write message");
+        .expect("Failed to write message");
 
         assert_eq!(&v[..], HEARTBEAT_V2);
     }
 
     /// A COMMAND_LONG message with a truncated payload (allowed for empty fields)
     pub const COMMAND_LONG_TRUNCATED_V2: &'static [u8] = &[
-        mavlink::MAV_STX_V2, 30, 0, 0, 0, 0, 50, //header
-        76, 0, 0, //msg ID
+        mavlink::MAV_STX_V2,
+        30,
+        0,
+        0,
+        0,
+        0,
+        50, //header
+        76,
+        0,
+        0, //msg ID
         //truncated payload:
-        0, 0, 230, 66, 0, 64, 156, 69, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 255, 1,
+        0,
+        0,
+        230,
+        66,
+        0,
+        64,
+        156,
+        69,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        0,
+        255,
+        1,
         // crc:
-        188, 195];
+        188,
+        195,
+    ];
 
     #[test]
     pub fn test_read_truncated_command_long() {
         let mut r = COMMAND_LONG_TRUNCATED_V2;
-        let (_header, recv_msg) = mavlink::read_v2_msg(&mut r).expect("Failed to parse COMMAND_LONG_TRUNCATED_V2");
+        let (_header, recv_msg) =
+            mavlink::read_v2_msg(&mut r).expect("Failed to parse COMMAND_LONG_TRUNCATED_V2");
 
         if let mavlink::common::MavMessage::COMMAND_LONG(recv_msg) = recv_msg {
-            assert_eq!(recv_msg.command, mavlink::common::MavCmd::MAV_CMD_SET_MESSAGE_INTERVAL);
+            assert_eq!(
+                recv_msg.command,
+                mavlink::common::MavCmd::MAV_CMD_SET_MESSAGE_INTERVAL
+            );
         } else {
             panic!("Decoded wrong message type")
         }
     }
-
-
-}
\ No newline at end of file
+}