mirror of
https://github.com/okalachev/flix.git
synced 2026-01-10 13:06:56 +00:00
Don't arm by mavlink command if throttle is not low
This commit is contained in:
@@ -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;
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user