From f9739dcd7ebc2ad79ac337cb10ef61e1ad1fb611 Mon Sep 17 00:00:00 2001 From: Oleg Kalachev Date: Fri, 29 Aug 2025 03:47:51 +0300 Subject: [PATCH] Don't arm by mavlink command if throttle is not low --- flix/mavlink.ino | 1 + 1 file changed, 1 insertion(+) diff --git a/flix/mavlink.ino b/flix/mavlink.ino index 18b70af..1ac180b 100644 --- a/flix/mavlink.ino +++ b/flix/mavlink.ino @@ -226,6 +226,7 @@ void handleMavlink(const void *_msg) { } if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) { + if (m.param1 && controlThrottle > 0.05) return; // don't arm if throttle is not low accepted = true; armed = m.param1 == 1; }