1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 20:35:33 +03:00

Reworked arming conditions.

This commit is contained in:
mikeller 2017-06-19 00:40:59 +12:00
parent fb0429597f
commit 31df82db2d
20 changed files with 149 additions and 107 deletions

View file

@ -144,11 +144,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
if (IS_RC_MODE_ACTIVE(BOXARM)) {
rcDisarmTicks = 0;
// Arming via ARM BOX
if (throttleStatus == THROTTLE_LOW) {
if (ARMING_FLAG(OK_TO_ARM)) {
mwArm();
}
}
tryArm();
} else {
// Disarming via ARM BOX
@ -156,9 +152,9 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
rcDisarmTicks++;
if (rcDisarmTicks > 3) {
if (armingConfig()->disarm_kill_switch) {
mwDisarm();
disarm();
} else if (throttleStatus == THROTTLE_LOW) {
mwDisarm();
disarm();
}
}
}
@ -173,7 +169,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
// Disarm on throttle down + yaw
if (rcSticks == THR_LO + YAW_LO + PIT_CE + ROL_CE) {
if (ARMING_FLAG(ARMED))
mwDisarm();
disarm();
else {
beeper(BEEPER_DISARM_REPEAT); // sound tone while stick held
rcDelayCommand = 0; // reset so disarm tone will repeat
@ -233,7 +229,8 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
if (rcSticks == THR_LO + YAW_HI + PIT_CE + ROL_CE) {
// Arm via YAW
mwArm();
tryArm();
return;
}
}