From dee20a31f19338daa69ebd8695ff651ca4ba12f4 Mon Sep 17 00:00:00 2001 From: mirkix <“mirkix@gmail.com”> Date: Tue, 22 Dec 2015 22:14:15 +0100 Subject: [PATCH] AP_Notify: Add gps_num_sats --- libraries/AP_GPS/AP_GPS.cpp | 1 + libraries/AP_Notify/AP_Notify.h | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 06c4f1d6af..0ad035ea51 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -428,6 +428,7 @@ AP_GPS::update(void) // update notify with gps status. We always base this on the primary_instance AP_Notify::flags.gps_status = state[primary_instance].status; + AP_Notify::flags.gps_num_sats = state[primary_instance].num_sats; } /* diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index 965434f58e..d4f201181e 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -55,6 +55,7 @@ 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_num_sats : 6; // number of sats 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