mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
Notify: remove baro_glitch reporting
This commit is contained in:
parent
0476558049
commit
8e8487c699
@ -60,7 +60,6 @@ public:
|
||||
uint32_t initialising : 1; // 1 if initialising and copter should not be moved
|
||||
uint32_t gps_status : 3; // 0 = no gps, 1 = no lock, 2 = 2d lock, 3 = 3d lock, 4 = dgps lock, 5 = rtk lock
|
||||
uint32_t gps_glitching : 1; // 1 if gps position is not good
|
||||
uint32_t baro_glitching : 1; // 1 if baro altitude is not good
|
||||
uint32_t armed : 1; // 0 = disarmed, 1 = armed
|
||||
uint32_t pre_arm_check : 1; // 0 = failing checks, 1 = passed
|
||||
uint32_t pre_arm_gps_check : 1; // 0 = failing pre-arm GPS checks, 1 = passed
|
||||
|
@ -228,16 +228,6 @@ void Buzzer::update()
|
||||
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);
|
||||
|
@ -75,7 +75,6 @@ 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 ekf_bad : 1; // 1 if ekf position has gone bad
|
||||
} _flags;
|
||||
|
||||
|
@ -153,11 +153,9 @@ void RGBLed::update_colours(void)
|
||||
|
||||
// radio and battery failsafe patter: flash yellow
|
||||
// gps failsafe pattern : flashing yellow and blue
|
||||
// baro glitching pattern : flashing yellow and purple
|
||||
// ekf_bad pattern : flashing yellow and red
|
||||
if (AP_Notify::flags.failsafe_radio || AP_Notify::flags.failsafe_battery ||
|
||||
AP_Notify::flags.failsafe_gps || AP_Notify::flags.gps_glitching ||
|
||||
AP_Notify::flags.baro_glitching ||
|
||||
AP_Notify::flags.ekf_bad) {
|
||||
switch(step) {
|
||||
case 0:
|
||||
@ -180,11 +178,6 @@ void RGBLed::update_colours(void)
|
||||
_red_des = _led_off;
|
||||
_blue_des = brightness;
|
||||
_green_des = _led_off;
|
||||
} else if (AP_Notify::flags.baro_glitching) {
|
||||
// purple on if baro glitching
|
||||
_red_des = brightness;
|
||||
_blue_des = brightness;
|
||||
_green_des = _led_off;
|
||||
} else if (AP_Notify::flags.ekf_bad) {
|
||||
// red on if ekf bad
|
||||
_red_des = brightness;
|
||||
|
Loading…
Reference in New Issue
Block a user