From 265e8a6c65675ef99c6a21f2cafc9bcf134a4451 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Ant=C3=B4nio=20Cardoso?= Date: Tue, 12 Nov 2024 21:52:10 -0300 Subject: [PATCH] src: lib: cli: Add --mavlink-system-id, --mavlink-component-id, --mavlink-heartbeat-frequency CLI args --- src/lib/cli.rs | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/src/lib/cli.rs b/src/lib/cli.rs index bf11209..bc3473b 100644 --- a/src/lib/cli.rs +++ b/src/lib/cli.rs @@ -61,6 +61,19 @@ struct Args { /// The timeout duration (in seconds) after which inactive UDP clients will be discarded. #[arg(long, default_value = "10")] udp_server_timeout: i16, + + /// Sets MAVLink system ID for this service + #[arg(long, default_value = "1")] + mavlink_system_id: u8, + + /// Sets the MAVLink component ID for this service, for more information, check: https://mavlink.io/en/messages/common.html#MAV_COMPONENT") + /// note: the default value 191 means MAV_COMP_ID_ONBOARD_COMPUTER + #[arg(long, default_value = "191")] + mavlink_component_id: u8, + + /// Sets the frequency of the MAVLink heartbeat message sent by the Mavlink Server + #[arg(long, default_value = "1")] + mavlink_heartbeat_frequency: f32, } #[instrument(level = "trace")] @@ -193,6 +206,21 @@ pub fn web_server() -> std::net::SocketAddrV4 { MANAGER.clap_matches.web_server } +#[instrument(level = "debug")] +pub fn mavlink_system_id() -> u8 { + MANAGER.clap_matches.mavlink_system_id +} + +#[instrument(level = "debug")] +pub fn mavlink_component_id() -> u8 { + MANAGER.clap_matches.mavlink_component_id +} + +#[instrument(level = "debug")] +pub fn mavlink_heartbeat_frequency() -> f32 { + MANAGER.clap_matches.mavlink_heartbeat_frequency +} + #[cfg(test)] mod tests { use super::*;