mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 08:45:36 +03:00
Merge branch 'feature-autodisarm' of https://github.com/ledvinap/cleanflight into ledvinap-feature-autodisarm
This commit is contained in:
commit
84b197d5f8
4 changed files with 18 additions and 0 deletions
|
@ -91,6 +91,7 @@ uint16_t cycleTime = 0; // this is the number in micro second to achieve
|
|||
int16_t headFreeModeHold;
|
||||
|
||||
int16_t telemTemperature1; // gyro sensor temperature
|
||||
static uint32_t disarmTime; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||
|
||||
extern uint8_t dynP8[3], dynI8[3], dynD8[3];
|
||||
extern failsafe_t *failsafe;
|
||||
|
@ -326,6 +327,8 @@ void mwArm(void)
|
|||
}
|
||||
}
|
||||
#endif
|
||||
disarmTime = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
@ -493,6 +496,18 @@ void processRx(void)
|
|||
resetErrorAngle();
|
||||
resetErrorGyro();
|
||||
}
|
||||
// When armed and motors aren't spinning, disarm board after delay so users without buzzer won't lose fingers.
|
||||
// mixTable constrains motor commands, so checking throttleStatus is enough
|
||||
if (ARMING_FLAG(ARMED)
|
||||
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)
|
||||
&& masterConfig.auto_disarm_delay != 0) {
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
if ((int32_t)(disarmTime - millis()) < 0) // delay is over
|
||||
mwDisarm();
|
||||
} else {
|
||||
disarmTime = millis() + masterConfig.auto_disarm_delay * 1000; // extend delay
|
||||
}
|
||||
}
|
||||
|
||||
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, masterConfig.retarded_arm, masterConfig.disarm_kill_switch);
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue