diff --git a/libraries/AP_Notify/Display.cpp b/libraries/AP_Notify/Display.cpp index 42814e1ca5..301cc862f3 100644 --- a/libraries/AP_Notify/Display.cpp +++ b/libraries/AP_Notify/Display.cpp @@ -407,7 +407,9 @@ void Display::update_all() update_text(0); update_mode(1); update_battery(2); +#if AP_GPS_ENABLED update_gps(3); +#endif //update_gps_sats(4); update_prearm(4); update_ekf(5); @@ -475,6 +477,7 @@ void Display::update_prearm(uint8_t r) } } +#if AP_GPS_ENABLED void Display::update_gps(uint8_t r) { static const char * gpsfixname[] = {"Other", "NoGPS","NoFix","2D","3D","DGPS", "RTK f", "RTK F"}; @@ -516,6 +519,7 @@ void Display::update_gps_sats(uint8_t r) draw_char(COLUMN(8), ROW(r), (AP_Notify::flags.gps_num_sats / 10) + '0'); draw_char(COLUMN(9), ROW(r), (AP_Notify::flags.gps_num_sats % 10) + '0'); } +#endif void Display::update_ekf(uint8_t r) { diff --git a/libraries/AP_Notify/RGBLed.cpp b/libraries/AP_Notify/RGBLed.cpp index a0fe9af19f..b00ebdff0f 100644 --- a/libraries/AP_Notify/RGBLed.cpp +++ b/libraries/AP_Notify/RGBLed.cpp @@ -138,10 +138,12 @@ uint32_t RGBLed::get_colour_sequence(void) const // solid green or blue if armed if (AP_Notify::flags.armed) { +#if AP_GPS_ENABLED // solid green if armed with GPS 3d lock if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D) { return sequence_armed; } +#endif // solid blue if armed with no GPS lock return sequence_armed_nogps; } @@ -150,6 +152,7 @@ uint32_t RGBLed::get_colour_sequence(void) const if (!AP_Notify::flags.pre_arm_check) { return sequence_prearm_failing; } +#if AP_GPS_ENABLED if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D_DGPS && AP_Notify::flags.pre_arm_gps_check) { return sequence_disarmed_good_dgps; } @@ -157,6 +160,7 @@ uint32_t RGBLed::get_colour_sequence(void) const if (AP_Notify::flags.gps_status >= AP_GPS::GPS_OK_FIX_3D && AP_Notify::flags.pre_arm_gps_check) { return sequence_disarmed_good_gps; } +#endif return sequence_disarmed_bad_gps; }