From 4c8227c050dae7eca7f5a9d08fca1363bc776356 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 22 Sep 2013 22:20:47 +0900 Subject: [PATCH] Copter: update AP_Notify for gps failsafe and glitching --- ArduCopter/AP_State.pde | 3 +++ ArduCopter/ArduCopter.pde | 3 ++- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduCopter/AP_State.pde b/ArduCopter/AP_State.pde index 75686cdd98..b14bd6e45a 100644 --- a/ArduCopter/AP_State.pde +++ b/ArduCopter/AP_State.pde @@ -80,6 +80,9 @@ void set_low_battery(bool b) static void set_failsafe_gps(bool b) { ap.failsafe_gps = b; + + // update AP_Notify + AP_Notify::flags.failsafe_gps = b; } // --------------------------------------------- diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 9770db7ca3..f2e92510e6 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1388,8 +1388,9 @@ static void update_GPS(void) // for performance monitoring gps_fix_count++; - // run glitch protection + // run glitch protection and update AP_Notify gps_glitch.check_position(); + AP_Notify::flags.gps_glitching = gps_glitch.glitching(); // check if we can initialise home yet if (!ap.home_is_set) {