Browse Source

AP_Notify: Add gps_num_sats

master
mirkix 9 years ago committed by Lucas De Marchi
parent
commit
dee20a31f1
  1. 1
      libraries/AP_GPS/AP_GPS.cpp
  2. 1
      libraries/AP_Notify/AP_Notify.h

1
libraries/AP_GPS/AP_GPS.cpp

@ -428,6 +428,7 @@ AP_GPS::update(void) @@ -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;
}
/*

1
libraries/AP_Notify/AP_Notify.h

@ -55,6 +55,7 @@ public: @@ -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

Loading…
Cancel
Save