mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +03:00
Merge branch 'refactoredBeeperCode_181_1' of
git://github.com/ethomas997/cleanflight into ethomas997-refactoredBeeperCode_181_1 Conflicts: src/main/flight/failsafe.c src/main/io/beeper.c src/main/mw.c
This commit is contained in:
commit
519586a5ce
15 changed files with 487 additions and 194 deletions
|
@ -242,6 +242,11 @@ void annexCode(void)
|
|||
if (feature(FEATURE_VBAT)) {
|
||||
updateBatteryVoltage();
|
||||
batteryState = calculateBatteryState();
|
||||
//handle beepers for battery levels
|
||||
if (batteryState == BATTERY_CRITICAL)
|
||||
beeper(BEEPER_BAT_CRIT_LOW); //critically low battery
|
||||
else if (batteryState == BATTERY_WARNING)
|
||||
beeper(BEEPER_BAT_LOW); //low battery
|
||||
}
|
||||
|
||||
if (feature(FEATURE_CURRENT_METER)) {
|
||||
|
@ -251,7 +256,7 @@ void annexCode(void)
|
|||
}
|
||||
}
|
||||
|
||||
beepcodeUpdateState(batteryState);
|
||||
beeperUpdate(); //call periodic beeper handler
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
LED0_ON;
|
||||
|
@ -317,6 +322,8 @@ void mwDisarm(void)
|
|||
finishBlackbox();
|
||||
}
|
||||
#endif
|
||||
|
||||
beeper(BEEPER_DISARMING); // emit disarm tone
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -355,6 +362,16 @@ void mwArm(void)
|
|||
#endif
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||
|
||||
//beep to indicate arming
|
||||
#ifdef GPS
|
||||
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && GPS_numSat >= 5)
|
||||
beeper(BEEPER_ARMING_GPS_FIX);
|
||||
else
|
||||
beeper(BEEPER_ARMING);
|
||||
#else
|
||||
beeper(BEEPER_ARMING);
|
||||
#endif
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
@ -380,9 +397,9 @@ void handleInflightCalibrationStickPosition(void)
|
|||
} else {
|
||||
AccInflightCalibrationArmed = !AccInflightCalibrationArmed;
|
||||
if (AccInflightCalibrationArmed) {
|
||||
queueConfirmationBeep(4);
|
||||
beeper(BEEPER_ACC_CALIBRATION);
|
||||
} else {
|
||||
queueConfirmationBeep(6);
|
||||
beeper(BEEPER_ACC_CALIBRATION_FAIL);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -497,6 +514,8 @@ void executePeriodicTasks(void)
|
|||
|
||||
void processRx(void)
|
||||
{
|
||||
static bool armedBeeperOn = false;
|
||||
|
||||
calculateRxChannelsAndUpdateFailsafe(currentTime);
|
||||
|
||||
// in 3D mode, we need to be able to disarm by switch at any time
|
||||
|
@ -522,18 +541,48 @@ void processRx(void)
|
|||
pidResetErrorAngle();
|
||||
pidResetErrorGyro();
|
||||
}
|
||||
// When armed and motors aren't spinning, disarm board after delay so users without buzzer won't lose fingers.
|
||||
|
||||
// When armed and motors aren't spinning, do beeps and then 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
|
||||
&& isUsingSticksForArming())
|
||||
{
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
if ((int32_t)(disarmAt - millis()) < 0) // delay is over
|
||||
mwDisarm();
|
||||
&& feature(FEATURE_MOTOR_STOP)
|
||||
&& !STATE(FIXED_WING)
|
||||
) {
|
||||
if (isUsingSticksForArming()) {
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
if (masterConfig.auto_disarm_delay != 0
|
||||
&& (int32_t)(disarmAt - millis()) < 0
|
||||
) {
|
||||
// auto-disarm configured and delay is over
|
||||
mwDisarm();
|
||||
armedBeeperOn = false;
|
||||
} else {
|
||||
// still armed; do warning beeps while armed
|
||||
beeper(BEEPER_ARMED);
|
||||
armedBeeperOn = true;
|
||||
}
|
||||
} else {
|
||||
// throttle is not low
|
||||
if (masterConfig.auto_disarm_delay != 0) {
|
||||
// extend disarm time
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000;
|
||||
}
|
||||
|
||||
if (armedBeeperOn) {
|
||||
beeper(BEEPER_STOP);
|
||||
armedBeeperOn = false;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
disarmAt = millis() + masterConfig.auto_disarm_delay * 1000; // extend delay
|
||||
// arming is via AUX switch; beep while throttle low
|
||||
if (throttleStatus == THROTTLE_LOW) {
|
||||
beeper(BEEPER_ARMED);
|
||||
armedBeeperOn = true;
|
||||
} else if (armedBeeperOn) {
|
||||
beeper(BEEPER_STOP);
|
||||
armedBeeperOn = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue