Fix stick arming auto-disarm timer not being reset
Fix code path that could prevent the auto-disarm timer from being reset leading to a possible immediate disarm if airmode was switched off while in flight.
This commit is contained in:
parent
799704cee3
commit
f0e2cf195b
|
@ -130,7 +130,7 @@ int16_t magHold;
|
||||||
|
|
||||||
static bool flipOverAfterCrashMode = false;
|
static bool flipOverAfterCrashMode = false;
|
||||||
|
|
||||||
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
static timeUs_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||||
|
|
||||||
bool isRXDataNew;
|
bool isRXDataNew;
|
||||||
static int lastArmingDisabledReason = 0;
|
static int lastArmingDisabledReason = 0;
|
||||||
|
@ -338,8 +338,11 @@ void tryArm(void)
|
||||||
if (ARMING_FLAG(ARMED)) {
|
if (ARMING_FLAG(ARMED)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
const timeUs_t currentTimeUs = micros();
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
if (micros() - getLastDshotBeaconCommandTimeUs() < DSHOT_BEACON_GUARD_DELAY_US) {
|
if (currentTimeUs - getLastDshotBeaconCommandTimeUs() < DSHOT_BEACON_GUARD_DELAY_US) {
|
||||||
if (tryingToArm == ARMING_DELAYED_DISARMED) {
|
if (tryingToArm == ARMING_DELAYED_DISARMED) {
|
||||||
if (isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH) && IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) {
|
if (isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH) && IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) {
|
||||||
tryingToArm = ARMING_DELAYED_CRASHFLIP;
|
tryingToArm = ARMING_DELAYED_CRASHFLIP;
|
||||||
|
@ -381,7 +384,7 @@ void tryArm(void)
|
||||||
}
|
}
|
||||||
imuQuaternionHeadfreeOffsetSet();
|
imuQuaternionHeadfreeOffsetSet();
|
||||||
|
|
||||||
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
disarmAt = currentTimeUs + armingConfig()->auto_disarm_delay * 1e6; // start disarm timeout, will be extended when throttle is nonzero
|
||||||
|
|
||||||
lastArmingDisabledReason = 0;
|
lastArmingDisabledReason = 0;
|
||||||
|
|
||||||
|
@ -666,6 +669,7 @@ bool processRx(timeUs_t currentTimeUs)
|
||||||
// When armed and motors aren't spinning, do beeps and then disarm
|
// When armed and motors aren't spinning, do beeps and then disarm
|
||||||
// board after delay so users without buzzer won't lose fingers.
|
// board after delay so users without buzzer won't lose fingers.
|
||||||
// mixTable constrains motor commands, so checking throttleStatus is enough
|
// mixTable constrains motor commands, so checking throttleStatus is enough
|
||||||
|
const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6;
|
||||||
if (ARMING_FLAG(ARMED)
|
if (ARMING_FLAG(ARMED)
|
||||||
&& featureIsEnabled(FEATURE_MOTOR_STOP)
|
&& featureIsEnabled(FEATURE_MOTOR_STOP)
|
||||||
&& !STATE(FIXED_WING)
|
&& !STATE(FIXED_WING)
|
||||||
|
@ -674,9 +678,7 @@ bool processRx(timeUs_t currentTimeUs)
|
||||||
) {
|
) {
|
||||||
if (isUsingSticksForArming()) {
|
if (isUsingSticksForArming()) {
|
||||||
if (throttleStatus == THROTTLE_LOW) {
|
if (throttleStatus == THROTTLE_LOW) {
|
||||||
if (armingConfig()->auto_disarm_delay != 0
|
if ((autoDisarmDelayUs > 0) && (currentTimeUs > disarmAt)) {
|
||||||
&& (int32_t)(disarmAt - millis()) < 0
|
|
||||||
) {
|
|
||||||
// auto-disarm configured and delay is over
|
// auto-disarm configured and delay is over
|
||||||
disarm();
|
disarm();
|
||||||
armedBeeperOn = false;
|
armedBeeperOn = false;
|
||||||
|
@ -686,11 +688,8 @@ bool processRx(timeUs_t currentTimeUs)
|
||||||
armedBeeperOn = true;
|
armedBeeperOn = true;
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// throttle is not low
|
// throttle is not low - extend disarm time
|
||||||
if (armingConfig()->auto_disarm_delay != 0) {
|
disarmAt = currentTimeUs + autoDisarmDelayUs;
|
||||||
// extend disarm time
|
|
||||||
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (armedBeeperOn) {
|
if (armedBeeperOn) {
|
||||||
beeperSilence();
|
beeperSilence();
|
||||||
|
@ -707,6 +706,8 @@ bool processRx(timeUs_t currentTimeUs)
|
||||||
armedBeeperOn = false;
|
armedBeeperOn = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
disarmAt = currentTimeUs + autoDisarmDelayUs; // extend auto-disarm timer
|
||||||
}
|
}
|
||||||
|
|
||||||
processRcStickPositions();
|
processRcStickPositions();
|
||||||
|
|
Loading…
Reference in New Issue