diff --git a/Cargo.toml b/Cargo.toml index 8ae58048c5..b099521299 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -19,8 +19,9 @@ proc-macro2 = "1.0.43" lazy_static = "1.2.0" serde = { version = "1.0.115", optional = true, features = ["derive"] } -[[bin]] +[[example]] name = "mavlink-dump" +path = "examples/mavlink-dump/src/main.rs" required-features = ["ardupilotmega"] [dependencies] diff --git a/examples/mavlink-dump/Cargo.toml b/examples/mavlink-dump/Cargo.toml new file mode 100644 index 0000000000..284ab5c890 --- /dev/null +++ b/examples/mavlink-dump/Cargo.toml @@ -0,0 +1,15 @@ +[package] +name = "mavlink-dump" +authors = [ + "Patrick José Pereira ", +] +license = "MIT/Apache-2.0" +edition = "2018" +version = "0.1.0" + +[profile.release] +opt-level = 3 +lto = true # Performs "fat" LTO which attempts to perform optimizations across all crates within the dependency graph + +[dependencies.mavlink] # MAVLink library +path = "../../" diff --git a/src/bin/mavlink-dump.rs b/examples/mavlink-dump/src/main.rs similarity index 95% rename from src/bin/mavlink-dump.rs rename to examples/mavlink-dump/src/main.rs index 9d30e84d40..f2f1043504 100644 --- a/src/bin/mavlink-dump.rs +++ b/examples/mavlink-dump/src/main.rs @@ -1,11 +1,6 @@ use mavlink::error::MessageReadError; -#[cfg(feature = "std")] use std::{env, sync::Arc, thread, time::Duration}; -#[cfg(not(feature = "std"))] -fn main() {} - -#[cfg(feature = "std")] fn main() { let args: Vec<_> = env::args().collect(); @@ -65,7 +60,6 @@ fn main() { } /// Create a heartbeat message using 'ardupilotmega' dialect -#[cfg(feature = "std")] pub fn heartbeat_message() -> mavlink::ardupilotmega::MavMessage { mavlink::ardupilotmega::MavMessage::HEARTBEAT(mavlink::ardupilotmega::HEARTBEAT_DATA { custom_mode: 0, @@ -78,7 +72,6 @@ pub fn heartbeat_message() -> mavlink::ardupilotmega::MavMessage { } /// Create a message requesting the parameters list -#[cfg(feature = "std")] pub fn request_parameters() -> mavlink::ardupilotmega::MavMessage { mavlink::ardupilotmega::MavMessage::PARAM_REQUEST_LIST( mavlink::ardupilotmega::PARAM_REQUEST_LIST_DATA { @@ -89,7 +82,6 @@ pub fn request_parameters() -> mavlink::ardupilotmega::MavMessage { } /// Create a message enabling data streaming -#[cfg(feature = "std")] pub fn request_stream() -> mavlink::ardupilotmega::MavMessage { mavlink::ardupilotmega::MavMessage::REQUEST_DATA_STREAM( mavlink::ardupilotmega::REQUEST_DATA_STREAM_DATA {