Notify: APM2 buzzer for arming, ekf and baro failures

This commit is contained in:
Randy Mackay 2014-07-28 21:28:34 +09:00
parent dcc74be4aa
commit 4d6588a479
2 changed files with 84 additions and 1 deletions

View File

@ -124,6 +124,54 @@ void Buzzer::update()
}
}
return;
case BARO_GLITCH:
// four fast tones
switch (_pattern_counter) {
case 1:
case 3:
case 5:
case 7:
case 9:
on(true);
break;
case 2:
case 4:
case 6:
case 8:
on(false);
break;
case 10:
on(false);
_pattern = NONE;
break;
default:
// do nothing
break;
}
return;
case EKF_BAD:
// four tones getting shorter)
switch (_pattern_counter) {
case 1:
case 5:
case 8:
case 10:
on(true);
break;
case 4:
case 7:
case 9:
on(false);
break;
case 11:
on(false);
_pattern = NONE;
break;
default:
// do nothing
break;
}
return;
default:
// do nothing
break;
@ -143,6 +191,16 @@ void Buzzer::update()
return;
}
// check arming failed
if (_flags.arming_failed != AP_Notify::flags.arming_failed) {
_flags.arming_failed = AP_Notify::flags.arming_failed;
if (_flags.arming_failed) {
// arming failed buzz
play_pattern(SINGLE_BUZZ);
}
return;
}
// check gps glitch
if (_flags.gps_glitching != AP_Notify::flags.gps_glitching) {
_flags.gps_glitching = AP_Notify::flags.gps_glitching;
@ -163,6 +221,26 @@ void Buzzer::update()
return;
}
// check ekf bad
if (_flags.ekf_bad != AP_Notify::flags.ekf_bad) {
_flags.ekf_bad = AP_Notify::flags.ekf_bad;
if (_flags.ekf_bad) {
// ekf bad warning buzz
play_pattern(EKF_BAD);
}
return;
}
// check baro glitch
if (_flags.baro_glitching != AP_Notify::flags.baro_glitching) {
_flags.baro_glitching = AP_Notify::flags.baro_glitching;
if (_flags.baro_glitching) {
// baro glitch warning buzz
play_pattern(BARO_GLITCH);
}
return;
}
// if battery failsafe constantly single buzz
if (AP_Notify::flags.failsafe_battery) {
play_pattern(SINGLE_BUZZ);

View File

@ -55,7 +55,9 @@ public:
SINGLE_BUZZ = 1,
DOUBLE_BUZZ = 2,
GPS_GLITCH = 3,
ARMING_BUZZ = 4
ARMING_BUZZ = 4,
BARO_GLITCH = 5,
EKF_BAD = 6
};
/// play_pattern - plays the defined buzzer pattern
@ -71,6 +73,9 @@ private:
uint8_t armed : 1; // 0 = disarmed, 1 = armed
uint8_t failsafe_battery : 1; // 1 if battery failsafe has triggered
uint8_t failsafe_gps : 1; // 1 if gps failsafe
uint8_t baro_glitching : 1; // 1 if baro alt is glitching
uint8_t arming_failed : 1; // 0 = failing checks, 1 = passed
uint8_t ekf_bad : 1; // 1 if ekf position has gone bad
} _flags;
uint8_t _counter; // reduces 50hz update down to 10hz for internal processing