Don't arm by mavlink command if throttle is not low

This commit is contained in:
Oleg Kalachev
2025-08-29 03:47:51 +03:00
parent 708c8f04dc
commit f9739dcd7e

View File

@@ -226,6 +226,7 @@ void handleMavlink(const void *_msg) {
} }
if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) { 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; accepted = true;
armed = m.param1 == 1; armed = m.param1 == 1;
} }