Browse Source

Copter: update AP_Notify for gps failsafe and glitching

mission-4.1.18
Randy Mackay 12 years ago
parent
commit
4c8227c050
  1. 3
      ArduCopter/AP_State.pde
  2. 3
      ArduCopter/ArduCopter.pde

3
ArduCopter/AP_State.pde

@ -80,6 +80,9 @@ void set_low_battery(bool b) @@ -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;
}
// ---------------------------------------------

3
ArduCopter/ArduCopter.pde

@ -1388,8 +1388,9 @@ static void update_GPS(void) @@ -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) {

Loading…
Cancel
Save