diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml
index 9011cc0c69..313eb75862 100644
--- a/.github/workflows/test.yml
+++ b/.github/workflows/test.yml
@@ -51,6 +51,10 @@ jobs:
- uses: dtolnay/rust-toolchain@master
with:
toolchain: 1.65.0
+ - uses: actions-rs/cargo@v1
+ with:
+ command: install
+ args: cross --locked
- uses: actions-rs/cargo@v1
with:
use-cross: true
@@ -103,7 +107,7 @@ jobs:
with:
use-cross: true
command: build
- args: --verbose --release --target=${{ matrix.TARGET }} ${{ matrix.FLAGS }}
+ args: --verbose --release --package=mavlink --target=${{ matrix.TARGET }} ${{ matrix.FLAGS }}
test-embedded-size:
needs: build
@@ -114,7 +118,7 @@ jobs:
with:
target: thumbv7em-none-eabihf
- name: Build
- run: cargo +nightly build --target thumbv7em-none-eabihf --manifest-path examples/embedded/Cargo.toml --out-dir $PWD --release -Z unstable-options
+ run: cargo +nightly build --target thumbv7em-none-eabihf --manifest-path mavlink/examples/embedded/Cargo.toml --out-dir $PWD --release -Z unstable-options
docs:
needs: internal-tests
diff --git a/.gitmodules b/.gitmodules
index 3fbebb0955..80bff682ff 100644
--- a/.gitmodules
+++ b/.gitmodules
@@ -1,3 +1,3 @@
-[submodule "mavlink"]
- path = mavlink
+[submodule "mavlink/mavlink"]
+ path = mavlink/mavlink
url = https://github.com/mavlink/mavlink
diff --git a/.idea/workspace.xml b/.idea/workspace.xml
new file mode 100644
index 0000000000..2a7f278391
--- /dev/null
+++ b/.idea/workspace.xml
@@ -0,0 +1,128 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1707604355173
+
+
+ 1707604355173
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/Cargo.toml b/Cargo.toml
index b099521299..65e9ef8b1d 100644
--- a/Cargo.toml
+++ b/Cargo.toml
@@ -1,105 +1,10 @@
+[workspace]
+members = ["mavlink", "mavlink-bindgen", "mavlink-core"]
+resolver = "1"
-[package]
-name = "mavlink"
-version = "0.12.2"
-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"
-license = "MIT/Apache-2.0"
-repository = "https://github.com/mavlink/rust-mavlink"
-edition = "2018"
-rust-version = "1.65.0"
-
-[build-dependencies]
-crc-any = { version = "2.3.0", default-features = false }
-quick-xml = "0.26"
-quote = "1"
-proc-macro2 = "1.0.43"
-lazy_static = "1.2.0"
-serde = { version = "1.0.115", optional = true, features = ["derive"] }
-
-[[example]]
-name = "mavlink-dump"
-path = "examples/mavlink-dump/src/main.rs"
-required-features = ["ardupilotmega"]
-
-[dependencies]
+[workspace.dependencies]
crc-any = { version = "2.3.5", default-features = false }
num-traits = { version = "0.2", default-features = false }
num-derive = "0.3.2"
bitflags = "1.2.1"
-serial = { version = "0.4", optional = true }
-serde = { version = "1.0.115", optional = true, features = ["derive"] }
byteorder = { version = "1.3.4", default-features = false }
-embedded-hal = { version = "0.2", optional = true }
-nb = { version = "1.0", optional = true }
-serde_arrays = { version = "0.1.0", optional = true }
-
-[features]
-"all" = [
- "ardupilotmega",
- "asluav",
- "common",
- "development",
- "icarous",
- "minimal",
- "python_array_test",
- "standard",
- "test",
- "ualberta",
- "uavionix",
- "avssuas",
- "cubepilot",
-]
-"ardupilotmega" = ["common", "icarous", "uavionix"]
-"asluav" = ["common"]
-"avssuas" = ["common"]
-"development" = ["common"]
-"matrixpilot" = ["common"]
-"minimal" = []
-"paparazzi" = ["common"]
-"python_array_test" = ["common"]
-"slugs" = ["common"]
-"standard" = ["common"]
-"test" = []
-"ualberta" = ["common"]
-"uavionix" = ["common"]
-"icarous" = []
-"common" = []
-"cubepilot" = ["common"]
-
-"all-dialects" = [
- "ardupilotmega",
- "asluav",
- "avssuas",
- "development",
- "matrixpilot",
- "minimal",
- "paparazzi",
- "python_array_test",
- "slugs",
- "standard",
- "test",
- "ualberta",
- "uavionix",
- "icarous",
- "common",
- "cubepilot",
-]
-
-"format-generated-code" = []
-"emit-description" = []
-"emit-extensions" = []
-"std" = ["byteorder/std"]
-"udp" = []
-"tcp" = []
-"direct-serial" = []
-"embedded" = ["embedded-hal", "nb"]
-"serde" = ["dep:serde", "dep:serde_arrays"]
-default = ["std", "tcp", "udp", "direct-serial", "serial", "serde", "ardupilotmega"]
-
-# build with all features on docs.rs so that users viewing documentation
-# can see everything
-[package.metadata.docs.rs]
-features = ["default", "all-dialects", "emit-description", "emit-extensions", "format-generated-code"]
diff --git a/build/main.rs b/build/main.rs
deleted file mode 100644
index 6c14eea2c8..0000000000
--- a/build/main.rs
+++ /dev/null
@@ -1,101 +0,0 @@
-#![recursion_limit = "256"]
-
-mod binder;
-mod parser;
-mod util;
-
-use crate::util::to_module_name;
-use std::env;
-use std::ffi::OsStr;
-use std::fs::{read_dir, File};
-use std::io::BufWriter;
-use std::path::{Path, PathBuf};
-use std::process::Command;
-
-pub fn main() {
- let src_dir = Path::new(env!("CARGO_MANIFEST_DIR"));
-
- // Update and init submodule
- if let Err(error) = Command::new("git")
- .arg("submodule")
- .arg("update")
- .arg("--init")
- .current_dir(src_dir)
- .status()
- {
- 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.flatten() {
- if let Err(error) = Command::new("git")
- .arg("apply")
- .arg(entry.path().as_os_str())
- .current_dir(&mavlink_dir)
- .status()
- {
- eprintln!("{error}");
- }
- }
- }
-
- let mut definitions_dir = src_dir.to_path_buf();
- definitions_dir.push("mavlink/message_definitions/v1.0");
-
- let out_dir = env::var("OUT_DIR").unwrap();
-
- 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 dest_path = Path::new(&out_dir).join(definition_rs);
- let mut outf = BufWriter::new(File::create(&dest_path).unwrap());
-
- // generate code
- parser::generate(
- &definitions_dir,
- &definition_file.into_string().unwrap(),
- &mut outf,
- );
- dbg_format_code(&out_dir, &dest_path);
-
- // Re-run build if definition file 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);
- dbg_format_code(out_dir, dest_path);
- }
-}
-
-#[cfg(feature = "format-generated-code")]
-fn dbg_format_code(cwd: impl AsRef, path: impl AsRef) {
- if let Err(error) = Command::new("rustfmt").arg(path).current_dir(cwd).status() {
- eprintln!("{error}");
- }
-}
-
-// Does nothing
-#[cfg(not(feature = "format-generated-code"))]
-fn dbg_format_code(_: impl AsRef, _: impl AsRef) {}
diff --git a/mavlink-bindgen/Cargo.toml b/mavlink-bindgen/Cargo.toml
new file mode 100644
index 0000000000..e5f3ee534b
--- /dev/null
+++ b/mavlink-bindgen/Cargo.toml
@@ -0,0 +1,26 @@
+[package]
+name = "mavlink-bindgen"
+version = "0.1.0"
+edition = "2021"
+
+# See more keys and their definitions at https://doc.rust-lang.org/cargo/reference/manifest.html
+
+[dependencies]
+crc-any = { workspace = true, default-features = false }
+quick-xml = "0.26"
+quote = "1"
+proc-macro2 = "1.0.43"
+lazy_static = "1.2.0"
+serde = { version = "1.0.115", optional = true, features = ["derive"] }
+clap = { version = "~4.3.24", optional = true, default-features =false, features = ["derive", "help", "usage", "error-context"] }
+thiserror = "1.0.56"
+
+# Required to support MSRV 1.65.0
+clap_lex = { version = "=0.5.0", optional=true }
+clap_builder = { version = "~4.3.24", optional=true}
+anstyle = { version = "=1.0.2", optional=true }
+anstyle-query = { version = "=1.0.0", optional=true }
+anstyle-parse = { version = "=0.2.1", optional=true }
+
+[features]
+cli = ["dep:clap", "dep:clap_lex", "dep:clap_builder", "dep:anstyle", "dep:anstyle-query", "dep:anstyle-parse"]
diff --git a/build/binder.rs b/mavlink-bindgen/src/binder.rs
similarity index 91%
rename from build/binder.rs
rename to mavlink-bindgen/src/binder.rs
index 099ef24e9b..b9a911cc1c 100644
--- a/build/binder.rs
+++ b/mavlink-bindgen/src/binder.rs
@@ -1,7 +1,7 @@
use quote::{format_ident, quote};
use std::io::Write;
-pub fn generate(modules: Vec, out: &mut W) {
+pub fn generate(modules: Vec<&str>, out: &mut W) {
let modules_tokens = modules.into_iter().map(|module| {
let module_ident = format_ident!("{}", module);
diff --git a/mavlink-bindgen/src/cli.rs b/mavlink-bindgen/src/cli.rs
new file mode 100644
index 0000000000..02eb59038f
--- /dev/null
+++ b/mavlink-bindgen/src/cli.rs
@@ -0,0 +1,28 @@
+use std::path::PathBuf;
+
+use clap::Parser;
+use mavlink_bindgen::{emit_cargo_build_messages, format_generated_code, generate};
+
+#[derive(Parser)]
+struct Cli {
+ definitions_dir: PathBuf,
+ destination_dir: PathBuf,
+ #[arg(long)]
+ format_generated_code: bool,
+ #[arg(long)]
+ emit_cargo_build_messages: bool,
+}
+
+pub fn main() {
+ let args = Cli::parse();
+ let result = generate(args.definitions_dir, args.destination_dir)
+ .expect("failed to generate MAVLink Rust bindings");
+
+ if args.format_generated_code {
+ format_generated_code(&result);
+ }
+
+ if args.emit_cargo_build_messages {
+ emit_cargo_build_messages(&result);
+ }
+}
diff --git a/mavlink-bindgen/src/error.rs b/mavlink-bindgen/src/error.rs
new file mode 100644
index 0000000000..fec283634b
--- /dev/null
+++ b/mavlink-bindgen/src/error.rs
@@ -0,0 +1,23 @@
+use thiserror::Error;
+
+#[derive(Error, Debug)]
+pub enum BindGenError {
+ /// Represents a failure to read the MAVLink definitions directory.
+ #[error("Could not read definitions directory {path}")]
+ CouldNotReadDefinitionsDirectory {
+ source: std::io::Error,
+ path: std::path::PathBuf,
+ },
+ /// Represents a failure to read a directory entry in the MAVLink definitions directory.
+ #[error("Could not read MAVLink definitions directory entry {path}")]
+ CouldNotReadDirectoryEntryInDefinitionsDirectory {
+ source: std::io::Error,
+ path: std::path::PathBuf,
+ },
+ /// Represents a failure to create a Rust file for the generated MAVLink bindings.
+ #[error("Could not create Rust bindings file {dest_path}")]
+ CouldNotCreateRustBindingsFile {
+ source: std::io::Error,
+ dest_path: std::path::PathBuf,
+ },
+}
diff --git a/mavlink-bindgen/src/lib.rs b/mavlink-bindgen/src/lib.rs
new file mode 100644
index 0000000000..da3145bed3
--- /dev/null
+++ b/mavlink-bindgen/src/lib.rs
@@ -0,0 +1,125 @@
+use crate::error::BindGenError;
+use std::fs::{read_dir, File};
+use std::io::BufWriter;
+use std::ops::Deref;
+use std::path::{Path, PathBuf};
+use std::process::Command;
+
+pub mod binder;
+pub mod error;
+pub mod parser;
+mod util;
+
+#[derive(Debug)]
+pub struct GeneratedBinding {
+ pub module_name: String,
+ pub mavlink_xml: PathBuf,
+ pub rust_module: PathBuf,
+}
+
+#[derive(Debug)]
+pub struct GeneratedBindings {
+ pub bindings: Vec,
+ pub mod_rs: PathBuf,
+}
+
+pub fn generate, P2: AsRef>(
+ definitions_dir: P1,
+ destination_dir: P2,
+) -> Result {
+ _generate(definitions_dir.as_ref(), destination_dir.as_ref())
+}
+
+fn _generate(
+ definitions_dir: &Path,
+ destination_dir: &Path,
+) -> Result {
+ let mut bindings = vec![];
+
+ for entry_maybe in read_dir(&definitions_dir).map_err(|source| {
+ BindGenError::CouldNotReadDefinitionsDirectory {
+ source,
+ path: definitions_dir.to_path_buf(),
+ }
+ })? {
+ let entry = entry_maybe.map_err(|source| {
+ BindGenError::CouldNotReadDirectoryEntryInDefinitionsDirectory {
+ source,
+ path: definitions_dir.to_path_buf(),
+ }
+ })?;
+
+ let definition_file = PathBuf::from(entry.file_name());
+ let module_name = util::to_module_name(&definition_file);
+
+ let mut definition_rs = PathBuf::from(&module_name);
+ definition_rs.set_extension("rs");
+
+ let dest_path = destination_dir.join(definition_rs);
+ let mut outf = BufWriter::new(File::create(&dest_path).map_err(|source| {
+ BindGenError::CouldNotCreateRustBindingsFile {
+ source,
+ dest_path: dest_path.clone(),
+ }
+ })?);
+
+ // generate code
+ parser::generate(&definitions_dir, &definition_file, &mut outf);
+
+ bindings.push(GeneratedBinding {
+ module_name,
+ mavlink_xml: definition_file,
+ rust_module: dest_path,
+ });
+ }
+
+ // output mod.rs
+ {
+ let dest_path = destination_dir.join("mod.rs");
+ let mut outf = File::create(&dest_path).map_err(|source| {
+ BindGenError::CouldNotCreateRustBindingsFile {
+ source,
+ dest_path: dest_path.clone(),
+ }
+ })?;
+
+ // generate code
+ binder::generate(
+ bindings
+ .iter()
+ .map(|binding| binding.module_name.deref())
+ .collect(),
+ &mut outf,
+ );
+
+ Ok(GeneratedBindings {
+ bindings,
+ mod_rs: dest_path,
+ })
+ }
+}
+
+pub fn format_generated_code(result: &GeneratedBindings) {
+ if let Err(error) = Command::new("rustfmt")
+ .args(
+ result
+ .bindings
+ .iter()
+ .map(|binding| binding.rust_module.clone()),
+ )
+ .arg(result.mod_rs.clone())
+ .status()
+ {
+ eprintln!("{error}");
+ }
+}
+
+pub fn emit_cargo_build_messages(result: &GeneratedBindings) {
+ for binding in &result.bindings {
+ // Re-run build if definition file changes
+ println!(
+ "cargo:rerun-if-changed={}",
+ binding.rust_module.to_string_lossy()
+ );
+ }
+}
diff --git a/mavlink-bindgen/src/main.rs b/mavlink-bindgen/src/main.rs
new file mode 100644
index 0000000000..660ba5ec7f
--- /dev/null
+++ b/mavlink-bindgen/src/main.rs
@@ -0,0 +1,11 @@
+#![recursion_limit = "256"]
+
+#[cfg(feature = "cli")]
+mod cli;
+
+pub fn main() {
+ #[cfg(feature = "cli")]
+ cli::main();
+ #[cfg(not(feature = "cli"))]
+ panic!("Compiled without cli feature");
+}
diff --git a/build/parser.rs b/mavlink-bindgen/src/parser.rs
similarity index 98%
rename from build/parser.rs
rename to mavlink-bindgen/src/parser.rs
index a0618c5319..0d273e663d 100644
--- a/build/parser.rs
+++ b/mavlink-bindgen/src/parser.rs
@@ -140,7 +140,6 @@ impl MavProfile {
quote! {
#comment
- use crate::MavlinkVersion;
#[allow(unused_imports)]
use num_derive::FromPrimitive;
#[allow(unused_imports)]
@@ -152,7 +151,7 @@ impl MavProfile {
#[allow(unused_imports)]
use bitflags::bitflags;
- use crate::{Message, MessageData, error::*, bytes::Bytes, bytes_mut::BytesMut};
+ use mavlink_core::{MavlinkVersion, Message, MessageData, bytes::Bytes, bytes_mut::BytesMut};
#[cfg(feature = "serde")]
use serde::{Serialize, Deserialize};
@@ -195,11 +194,11 @@ impl MavProfile {
let id_width = format_ident!("u32");
quote! {
- fn parse(version: MavlinkVersion, id: #id_width, payload: &[u8]) -> Result {
+ fn parse(version: MavlinkVersion, id: #id_width, payload: &[u8]) -> Result {
match id {
#(#structs::ID => #structs::deser(version, payload).map(Self::#enums),)*
_ => {
- Err(ParserError::UnknownMessage { id })
+ Err(::mavlink_core::error::ParserError::UnknownMessage { id })
},
}
}
@@ -506,7 +505,7 @@ impl MavMessage {
#(#ser_vars)*
if matches!(version, MavlinkVersion::V2) {
let len = __tmp.len();
- crate::remove_trailing_zeroes(&bytes[..len])
+ ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
} else {
__tmp.len()
}
@@ -606,7 +605,7 @@ impl MavMessage {
const EXTRA_CRC: u8 = #extra_crc;
const ENCODED_LEN: usize = #msg_encoded_len;
- fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result {
+ fn deser(_version: MavlinkVersion, __input: &[u8]) -> Result {
#deser_vars
}
@@ -718,7 +717,7 @@ impl MavField {
quote! {
#tmp
#name = #enum_name_ident::from_bits(tmp & #enum_name_ident::all().bits())
- .ok_or(ParserError::InvalidFlag { flag_type: #enum_name, value: tmp as u32 })?;
+ .ok_or(::mavlink_core::error::ParserError::InvalidFlag { flag_type: #enum_name, value: tmp as u32 })?;
}
} else {
panic!("Display option not implemented");
@@ -730,7 +729,7 @@ impl MavField {
quote!(
#tmp
#name = FromPrimitive::#val(tmp)
- .ok_or(ParserError::InvalidEnum { enum_type: #enum_name, value: tmp as u32 })?;
+ .ok_or(::mavlink_core::error::ParserError::InvalidEnum { enum_type: #enum_name, value: tmp as u32 })?;
)
}
} else {
@@ -1032,7 +1031,7 @@ fn is_valid_parent(p: Option, s: MavXmlElement) -> bool {
pub fn parse_profile(
definitions_dir: &Path,
- definition_file: &String,
+ definition_file: &Path,
parsed_files: &mut HashSet,
) -> MavProfile {
let in_path = Path::new(&definitions_dir).join(definition_file);
@@ -1045,7 +1044,7 @@ pub fn parse_profile(
let mut message = MavMessage::default();
let mut mavenum = MavEnum::default();
let mut entry = MavEnumEntry::default();
- let mut include = String::new();
+ let mut include = PathBuf::new();
let mut paramid: Option = None;
let mut xml_filter = MavXmlFilter::default();
@@ -1283,7 +1282,7 @@ pub fn parse_profile(
}
}
(Some(&Include), Some(&Mavlink)) => {
- include = s.replace('\n', "");
+ include = PathBuf::from(s.replace('\n', ""));
}
(Some(&Version), Some(&Mavlink)) => {
eprintln!("TODO: version {s:?}");
@@ -1360,7 +1359,7 @@ pub fn parse_profile(
/// Generate protobuf represenation of mavlink message set
/// Generate rust representation of mavlink message set with appropriate conversion methods
-pub fn generate(definitions_dir: &Path, definition_file: &String, output_rust: &mut W) {
+pub fn generate(definitions_dir: &Path, definition_file: &Path, output_rust: &mut W) {
let mut parsed_files: HashSet = HashSet::new();
let profile = parse_profile(definitions_dir, definition_file, &mut parsed_files);
diff --git a/build/util.rs b/mavlink-bindgen/src/util.rs
similarity index 100%
rename from build/util.rs
rename to mavlink-bindgen/src/util.rs
diff --git a/mavlink-core/Cargo.toml b/mavlink-core/Cargo.toml
new file mode 100644
index 0000000000..17940867be
--- /dev/null
+++ b/mavlink-core/Cargo.toml
@@ -0,0 +1,28 @@
+[package]
+name = "mavlink-core"
+version = "0.12.2"
+authors = ["Todd Stellanova", "Michal Podhradsky", "Kevin Mehall", "Tim Ryan", "Patrick José Pereira", "Ibiyemi Abiodun"]
+description = "Implements the MAVLink data interchange format for UAVs."
+readme = "README.md"
+license = "MIT/Apache-2.0"
+repository = "https://github.com/mavlink/rust-mavlink"
+edition = "2018"
+rust-version = "1.65.0"
+
+[dependencies]
+crc-any = { workspace = true, default-features = false }
+byteorder = { workspace = true, default-features = false }
+embedded-hal = { version = "0.2", optional = true }
+nb = { version = "1.0", optional = true }
+serde = { version = "1.0.115", optional = true, features = ["derive"] }
+serde_arrays = { version = "0.1.0", optional = true }
+serial = { version = "0.4", optional = true }
+
+[features]
+"std" = ["byteorder/std"]
+"udp" = []
+"tcp" = []
+"direct-serial" = ["serial"]
+"embedded" = ["embedded-hal", "nb"]
+"serde" = ["dep:serde", "dep:serde_arrays"]
+default = ["std", "tcp", "udp", "direct-serial", "serde"]
diff --git a/src/bytes.rs b/mavlink-core/src/bytes.rs
similarity index 100%
rename from src/bytes.rs
rename to mavlink-core/src/bytes.rs
diff --git a/src/bytes_mut.rs b/mavlink-core/src/bytes_mut.rs
similarity index 100%
rename from src/bytes_mut.rs
rename to mavlink-core/src/bytes_mut.rs
diff --git a/src/connection/direct_serial.rs b/mavlink-core/src/connection/direct_serial.rs
similarity index 100%
rename from src/connection/direct_serial.rs
rename to mavlink-core/src/connection/direct_serial.rs
diff --git a/src/connection/file.rs b/mavlink-core/src/connection/file.rs
similarity index 100%
rename from src/connection/file.rs
rename to mavlink-core/src/connection/file.rs
diff --git a/src/connection/mod.rs b/mavlink-core/src/connection/mod.rs
similarity index 100%
rename from src/connection/mod.rs
rename to mavlink-core/src/connection/mod.rs
diff --git a/src/connection/tcp.rs b/mavlink-core/src/connection/tcp.rs
similarity index 100%
rename from src/connection/tcp.rs
rename to mavlink-core/src/connection/tcp.rs
diff --git a/src/connection/udp.rs b/mavlink-core/src/connection/udp.rs
similarity index 100%
rename from src/connection/udp.rs
rename to mavlink-core/src/connection/udp.rs
diff --git a/src/embedded.rs b/mavlink-core/src/embedded.rs
similarity index 100%
rename from src/embedded.rs
rename to mavlink-core/src/embedded.rs
diff --git a/src/error.rs b/mavlink-core/src/error.rs
similarity index 100%
rename from src/error.rs
rename to mavlink-core/src/error.rs
diff --git a/src/lib.rs b/mavlink-core/src/lib.rs
similarity index 99%
rename from src/lib.rs
rename to mavlink-core/src/lib.rs
index 409a96a4b0..c5f86e4ac1 100644
--- a/src/lib.rs
+++ b/mavlink-core/src/lib.rs
@@ -30,12 +30,7 @@ use std::io::{Read, Write};
#[cfg(feature = "std")]
use byteorder::ReadBytesExt;
-#[cfg(feature = "std")]
-mod connection;
-#[cfg(feature = "std")]
-pub use self::connection::{connect, MavConnection};
-
-mod utils;
+pub mod utils;
#[allow(unused_imports)]
use utils::{remove_trailing_zeroes, RustDefault};
@@ -46,12 +41,13 @@ use crate::{bytes::Bytes, error::ParserError};
use crc_any::CRCu16;
-// include generate definitions
-include!(concat!(env!("OUT_DIR"), "/mod.rs"));
-
pub mod bytes;
pub mod bytes_mut;
+#[cfg(feature = "std")]
+mod connection;
pub mod error;
+#[cfg(feature = "std")]
+pub use self::connection::{connect, MavConnection};
#[cfg(feature = "embedded")]
pub mod embedded;
diff --git a/src/utils.rs b/mavlink-core/src/utils.rs
similarity index 97%
rename from src/utils.rs
rename to mavlink-core/src/utils.rs
index 486c2ea0bb..c0516c154e 100644
--- a/src/utils.rs
+++ b/mavlink-core/src/utils.rs
@@ -4,7 +4,7 @@
///
/// There must always be at least one remaining byte even if it is a
/// zero byte.
-pub(crate) fn remove_trailing_zeroes(data: &[u8]) -> usize {
+pub fn remove_trailing_zeroes(data: &[u8]) -> usize {
let mut len = data.len();
for b in data[1..].iter().rev() {
diff --git a/mavlink/Cargo.toml b/mavlink/Cargo.toml
new file mode 100644
index 0000000000..728e630a37
--- /dev/null
+++ b/mavlink/Cargo.toml
@@ -0,0 +1,96 @@
+
+[package]
+name = "mavlink"
+version = "0.12.2"
+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"
+license = "MIT/Apache-2.0"
+repository = "https://github.com/mavlink/rust-mavlink"
+edition = "2018"
+rust-version = "1.65.0"
+
+[build-dependencies]
+mavlink-bindgen = { path = "../mavlink-bindgen", default-features = false}
+
+[[example]]
+name = "mavlink-dump"
+path = "examples/mavlink-dump/src/main.rs"
+required-features = ["ardupilotmega"]
+
+[dependencies]
+mavlink-core = { path = "../mavlink-core", default-features = false}
+num-traits = { workspace = true, default-features = false }
+num-derive = { workspace = true }
+bitflags = { workspace = true }
+serde = { version = "1.0.115", optional = true, features = ["derive"] }
+serde_arrays = { version = "0.1.0", optional = true }
+
+[features]
+"all" = [
+ "ardupilotmega",
+ "asluav",
+ "common",
+ "development",
+ "icarous",
+ "minimal",
+ "python_array_test",
+ "standard",
+ "test",
+ "ualberta",
+ "uavionix",
+ "avssuas",
+ "cubepilot",
+]
+"ardupilotmega" = ["common", "icarous", "uavionix"]
+"asluav" = ["common"]
+"avssuas" = ["common"]
+"development" = ["common"]
+"matrixpilot" = ["common"]
+"minimal" = []
+"paparazzi" = ["common"]
+"python_array_test" = ["common"]
+"slugs" = ["common"]
+"standard" = ["common"]
+"test" = []
+"ualberta" = ["common"]
+"uavionix" = ["common"]
+"icarous" = []
+"common" = []
+"cubepilot" = ["common"]
+
+"all-dialects" = [
+ "ardupilotmega",
+ "asluav",
+ "avssuas",
+ "development",
+ "matrixpilot",
+ "minimal",
+ "paparazzi",
+ "python_array_test",
+ "slugs",
+ "standard",
+ "test",
+ "ualberta",
+ "uavionix",
+ "icarous",
+ "common",
+ "cubepilot",
+]
+
+"format-generated-code" = []
+"emit-description" = []
+"emit-extensions" = []
+"std" = ["mavlink-core/std"]
+"udp" = ["mavlink-core/udp"]
+"tcp" = ["mavlink-core/tcp"]
+"direct-serial" = ["mavlink-core/direct-serial"]
+"embedded" = ["mavlink-core/embedded"]
+"serde" = ["mavlink-core/serde", "dep:serde", "dep:serde_arrays"]
+default = ["std", "tcp", "udp", "direct-serial", "serde", "ardupilotmega"]
+
+# build with all features on docs.rs so that users viewing documentation
+# can see everything
+[package.metadata.docs.rs]
+features = ["default", "all-dialects", "emit-description", "emit-extensions", "format-generated-code"]
diff --git a/mavlink/build/main.rs b/mavlink/build/main.rs
new file mode 100644
index 0000000000..7206d20658
--- /dev/null
+++ b/mavlink/build/main.rs
@@ -0,0 +1,53 @@
+#![recursion_limit = "256"]
+
+use std::env;
+use std::fs::read_dir;
+use std::path::Path;
+use std::process::Command;
+
+pub fn main() {
+ let src_dir = Path::new(env!("CARGO_MANIFEST_DIR"));
+
+ // Update and init submodule
+ if let Err(error) = Command::new("git")
+ .arg("submodule")
+ .arg("update")
+ .arg("--init")
+ .current_dir(src_dir)
+ .status()
+ {
+ 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.flatten() {
+ if let Err(error) = Command::new("git")
+ .arg("apply")
+ .arg(entry.path().as_os_str())
+ .current_dir(&mavlink_dir)
+ .status()
+ {
+ eprintln!("{error}");
+ }
+ }
+ }
+
+ let mut definitions_dir = src_dir.to_path_buf();
+ definitions_dir.push("mavlink/message_definitions/v1.0");
+
+ let out_dir = env::var("OUT_DIR").unwrap();
+
+ let result = mavlink_bindgen::generate(definitions_dir, out_dir)
+ .expect("Failed to generate Rust MAVLink bindings");
+
+ #[cfg(feature = "format-generated-code")]
+ mavlink_bindgen::format_generated_code(&result);
+
+ mavlink_bindgen::emit_cargo_build_messages(&result);
+}
diff --git a/examples/embedded/.cargo/config.toml b/mavlink/examples/embedded/.cargo/config.toml
similarity index 100%
rename from examples/embedded/.cargo/config.toml
rename to mavlink/examples/embedded/.cargo/config.toml
diff --git a/examples/embedded/Cargo.toml b/mavlink/examples/embedded/Cargo.toml
similarity index 98%
rename from examples/embedded/Cargo.toml
rename to mavlink/examples/embedded/Cargo.toml
index 4f9fd15e7e..717a0c94d1 100644
--- a/examples/embedded/Cargo.toml
+++ b/mavlink/examples/embedded/Cargo.toml
@@ -20,3 +20,5 @@ stm32f3xx-hal = { version = "0.9", features = ["stm32f303xe"] } # HAL for stm32f
path = "../../"
features = ["ardupilotmega", "embedded"]
default-features = false
+
+[workspace]
\ No newline at end of file
diff --git a/examples/embedded/README.md b/mavlink/examples/embedded/README.md
similarity index 100%
rename from examples/embedded/README.md
rename to mavlink/examples/embedded/README.md
diff --git a/examples/embedded/memory.x b/mavlink/examples/embedded/memory.x
similarity index 100%
rename from examples/embedded/memory.x
rename to mavlink/examples/embedded/memory.x
diff --git a/examples/embedded/src/main.rs b/mavlink/examples/embedded/src/main.rs
similarity index 100%
rename from examples/embedded/src/main.rs
rename to mavlink/examples/embedded/src/main.rs
diff --git a/examples/mavlink-dump/Cargo.toml b/mavlink/examples/mavlink-dump/Cargo.toml
similarity index 100%
rename from examples/mavlink-dump/Cargo.toml
rename to mavlink/examples/mavlink-dump/Cargo.toml
diff --git a/examples/mavlink-dump/src/main.rs b/mavlink/examples/mavlink-dump/src/main.rs
similarity index 100%
rename from examples/mavlink-dump/src/main.rs
rename to mavlink/examples/mavlink-dump/src/main.rs
diff --git a/mavlink b/mavlink/mavlink
similarity index 100%
rename from mavlink
rename to mavlink/mavlink
diff --git a/rustfmt.toml b/mavlink/rustfmt.toml
similarity index 100%
rename from rustfmt.toml
rename to mavlink/rustfmt.toml
diff --git a/mavlink/src/lib.rs b/mavlink/src/lib.rs
new file mode 100644
index 0000000000..a1b71eaa5a
--- /dev/null
+++ b/mavlink/src/lib.rs
@@ -0,0 +1,5 @@
+#![cfg_attr(not(feature = "std"), no_std)]
+// include generate definitions
+include!(concat!(env!("OUT_DIR"), "/mod.rs"));
+
+pub use mavlink_core::*;
diff --git a/tests/direct_serial_tests.rs b/mavlink/tests/direct_serial_tests.rs
similarity index 100%
rename from tests/direct_serial_tests.rs
rename to mavlink/tests/direct_serial_tests.rs
diff --git a/tests/encode_decode_tests.rs b/mavlink/tests/encode_decode_tests.rs
similarity index 100%
rename from tests/encode_decode_tests.rs
rename to mavlink/tests/encode_decode_tests.rs
diff --git a/tests/helper_tests.rs b/mavlink/tests/helper_tests.rs
similarity index 100%
rename from tests/helper_tests.rs
rename to mavlink/tests/helper_tests.rs
diff --git a/tests/log.tlog b/mavlink/tests/log.tlog
similarity index 100%
rename from tests/log.tlog
rename to mavlink/tests/log.tlog
diff --git a/tests/mav_frame_tests.rs b/mavlink/tests/mav_frame_tests.rs
similarity index 100%
rename from tests/mav_frame_tests.rs
rename to mavlink/tests/mav_frame_tests.rs
diff --git a/tests/process_log_files.rs b/mavlink/tests/process_log_files.rs
similarity index 100%
rename from tests/process_log_files.rs
rename to mavlink/tests/process_log_files.rs
diff --git a/tests/tcp_loopback_tests.rs b/mavlink/tests/tcp_loopback_tests.rs
similarity index 100%
rename from tests/tcp_loopback_tests.rs
rename to mavlink/tests/tcp_loopback_tests.rs
diff --git a/tests/test_shared/mod.rs b/mavlink/tests/test_shared/mod.rs
similarity index 100%
rename from tests/test_shared/mod.rs
rename to mavlink/tests/test_shared/mod.rs
diff --git a/tests/udp_loopback_tests.rs b/mavlink/tests/udp_loopback_tests.rs
similarity index 100%
rename from tests/udp_loopback_tests.rs
rename to mavlink/tests/udp_loopback_tests.rs
diff --git a/tests/v1_encode_decode_tests.rs b/mavlink/tests/v1_encode_decode_tests.rs
similarity index 100%
rename from tests/v1_encode_decode_tests.rs
rename to mavlink/tests/v1_encode_decode_tests.rs
diff --git a/tests/v2_encode_decode_tests.rs b/mavlink/tests/v2_encode_decode_tests.rs
similarity index 100%
rename from tests/v2_encode_decode_tests.rs
rename to mavlink/tests/v2_encode_decode_tests.rs