From 0dc985a6abd77a46cdab08d5118b205cdd75cfac Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 13 Mar 2015 11:02:36 +0900 Subject: [PATCH] Notify: remove GPS glitch notification --- libraries/AP_Notify/AP_Notify.h | 2 -- libraries/AP_Notify/Buzzer.cpp | 43 ------------------------- libraries/AP_Notify/Buzzer.h | 4 +-- libraries/AP_Notify/ExternalLED.cpp | 5 +-- libraries/AP_Notify/RGBLed.cpp | 8 +---- libraries/AP_Notify/ToneAlarm_Linux.cpp | 18 ----------- libraries/AP_Notify/ToneAlarm_Linux.h | 2 -- libraries/AP_Notify/ToneAlarm_PX4.h | 1 - 8 files changed, 3 insertions(+), 80 deletions(-) diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index 4221069711..2ff2bd1273 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -59,7 +59,6 @@ public: struct notify_flags_type { 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 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 @@ -67,7 +66,6 @@ public: uint32_t esc_calibration : 1; // 1 if calibrating escs uint32_t failsafe_radio : 1; // 1 if radio failsafe uint32_t failsafe_battery : 1; // 1 if battery failsafe - uint32_t failsafe_gps : 1; // 1 if gps failsafe uint32_t parachute_release : 1; // 1 if parachute is being released uint32_t ekf_bad : 1; // 1 if ekf is reporting problems uint32_t autopilot_mode : 1; // 1 if vehicle is in an autopilot flight mode (only used by OreoLEDs) diff --git a/libraries/AP_Notify/Buzzer.cpp b/libraries/AP_Notify/Buzzer.cpp index 9884c1f5a2..67487b9691 100644 --- a/libraries/AP_Notify/Buzzer.cpp +++ b/libraries/AP_Notify/Buzzer.cpp @@ -94,29 +94,6 @@ void Buzzer::update() break; } return; - case GPS_GLITCH: - // play bethoven's 5th type buzz (three fast, one long) - switch (_pattern_counter) { - case 1: - case 3: - case 5: - case 7: - on(true); - break; - case 2: - case 4: - case 6: - on(false); - break; - case 17: - on(false); - _pattern = NONE; - break; - default: - // do nothing - break; - } - return; case ARMING_BUZZ: // record start time if (_pattern_counter == 1) { @@ -198,26 +175,6 @@ void Buzzer::update() return; } - // check gps glitch - if (_flags.gps_glitching != AP_Notify::flags.gps_glitching) { - _flags.gps_glitching = AP_Notify::flags.gps_glitching; - if (_flags.gps_glitching) { - // gps glitch warning buzz - play_pattern(GPS_GLITCH); - } - return; - } - - // check gps failsafe - if (_flags.failsafe_gps != AP_Notify::flags.failsafe_gps) { - _flags.failsafe_gps = AP_Notify::flags.failsafe_gps; - if (_flags.failsafe_gps) { - // gps glitch warning buzz - play_pattern(GPS_GLITCH); - } - return; - } - // check ekf bad if (_flags.ekf_bad != AP_Notify::flags.ekf_bad) { _flags.ekf_bad = AP_Notify::flags.ekf_bad; diff --git a/libraries/AP_Notify/Buzzer.h b/libraries/AP_Notify/Buzzer.h index b1eb76e4b9..27f9d88dbe 100644 --- a/libraries/AP_Notify/Buzzer.h +++ b/libraries/AP_Notify/Buzzer.h @@ -56,7 +56,7 @@ public: NONE = 0, SINGLE_BUZZ = 1, DOUBLE_BUZZ = 2, - GPS_GLITCH = 3, + GPS_GLITCH = 3, // not used ARMING_BUZZ = 4, BARO_GLITCH = 5, EKF_BAD = 6 @@ -70,11 +70,9 @@ private: /// buzzer_flag_type - bitmask of current state and ap_notify states we track struct buzzer_flag_type { uint8_t on : 1; // 1 if the buzzer is currently on - uint8_t gps_glitching : 1; // 1 if gps position is not good uint8_t arming : 1; // 1 if we are beginning the arming process 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 ekf_bad : 1; // 1 if ekf position has gone bad } _flags; diff --git a/libraries/AP_Notify/ExternalLED.cpp b/libraries/AP_Notify/ExternalLED.cpp index d6e076213f..be06fe7215 100644 --- a/libraries/AP_Notify/ExternalLED.cpp +++ b/libraries/AP_Notify/ExternalLED.cpp @@ -195,10 +195,7 @@ void ExternalLED::update(void) if (AP_Notify::flags.failsafe_battery || AP_Notify::flags.failsafe_radio) { // radio or battery failsafe indicated by fast flashing set_pattern(FAST_FLASH); - }else if(AP_Notify::flags.failsafe_gps || AP_Notify::flags.gps_glitching) - // gps failsafe indicated by oscillating - set_pattern(OSCILLATE); - else{ + } else { // otherwise do whatever the armed led is doing motor_led1(_flags.armedled_on); motor_led2(_flags.armedled_on); diff --git a/libraries/AP_Notify/RGBLed.cpp b/libraries/AP_Notify/RGBLed.cpp index 94a7425df5..185dae7f54 100644 --- a/libraries/AP_Notify/RGBLed.cpp +++ b/libraries/AP_Notify/RGBLed.cpp @@ -155,7 +155,6 @@ void RGBLed::update_colours(void) // gps failsafe pattern : flashing yellow and blue // 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.ekf_bad) { switch(step) { case 0: @@ -173,12 +172,7 @@ void RGBLed::update_colours(void) case 7: case 8: case 9: - if (AP_Notify::flags.failsafe_gps || AP_Notify::flags.gps_glitching) { - // blue on for gps failsafe or glitching - _red_des = _led_off; - _blue_des = brightness; - _green_des = _led_off; - } else if (AP_Notify::flags.ekf_bad) { + if (AP_Notify::flags.ekf_bad) { // red on if ekf bad _red_des = brightness; _blue_des = _led_off; diff --git a/libraries/AP_Notify/ToneAlarm_Linux.cpp b/libraries/AP_Notify/ToneAlarm_Linux.cpp index 47679d576b..f26c38c029 100644 --- a/libraries/AP_Notify/ToneAlarm_Linux.cpp +++ b/libraries/AP_Notify/ToneAlarm_Linux.cpp @@ -91,24 +91,6 @@ void ToneAlarm_Linux::update() } } - // check gps glitch - if (flags.gps_glitching != AP_Notify::flags.gps_glitching) { - flags.gps_glitching = AP_Notify::flags.gps_glitching; - if (flags.gps_glitching) { - // gps glitch warning tune - play_tune(TONE_GPS_WARNING_TUNE); - } - } - - // check gps failsafe - if (flags.failsafe_gps != AP_Notify::flags.failsafe_gps) { - flags.failsafe_gps = AP_Notify::flags.failsafe_gps; - if (flags.failsafe_gps) { - // gps glitch warning tune - play_tune(TONE_GPS_WARNING_TUNE); - } - } - // check parachute release if (flags.parachute_release != AP_Notify::flags.parachute_release) { flags.parachute_release = AP_Notify::flags.parachute_release; diff --git a/libraries/AP_Notify/ToneAlarm_Linux.h b/libraries/AP_Notify/ToneAlarm_Linux.h index 6104f614f2..072c0803dd 100644 --- a/libraries/AP_Notify/ToneAlarm_Linux.h +++ b/libraries/AP_Notify/ToneAlarm_Linux.h @@ -42,8 +42,6 @@ private: struct tonealarm_type { bool armed : 1; // false = disarmed, true = armed bool failsafe_battery : 1; // true if battery failsafe - bool gps_glitching : 1; // true if gps position is not good - bool failsafe_gps : 1; // true if gps failsafe bool parachute_release : 1; // true if parachute is being released } flags; }; diff --git a/libraries/AP_Notify/ToneAlarm_PX4.h b/libraries/AP_Notify/ToneAlarm_PX4.h index e9f2ef618e..96bb8bd0cb 100644 --- a/libraries/AP_Notify/ToneAlarm_PX4.h +++ b/libraries/AP_Notify/ToneAlarm_PX4.h @@ -51,7 +51,6 @@ private: struct tonealarm_type { uint8_t armed : 1; // 0 = disarmed, 1 = armed uint8_t failsafe_battery : 1; // 1 if battery failsafe - uint8_t failsafe_gps : 1; // 1 if gps failsafe uint8_t parachute_release : 1; // 1 if parachute is being released uint8_t pre_arm_check : 1; // 0 = failing checks, 1 = passed uint8_t failsafe_radio : 1; // 1 if radio failsafe