Copter: only report gps glitch when usb disconnected

This commit is contained in:
Randy Mackay 2014-02-11 11:43:24 +09:00
parent 681dafcfba
commit 7e8438cfc9
2 changed files with 5 additions and 3 deletions

View File

@ -1236,6 +1236,7 @@ static void update_GPS(void)
{
static uint32_t last_gps_reading; // time of last gps message
static uint8_t ground_start_count = 10; // counter used to grab at least 10 reads before commiting the Home location
bool report_gps_glitch;
g_gps->update();
@ -1251,13 +1252,14 @@ static void update_GPS(void)
// run glitch protection and update AP_Notify if home has been initialised
if (ap.home_is_set) {
gps_glitch.check_position();
if (AP_Notify::flags.gps_glitching != gps_glitch.glitching()) {
report_gps_glitch = (gps_glitch.glitching() && !ap.usb_connected);
if (AP_Notify::flags.gps_glitching != report_gps_glitch) {
if (gps_glitch.glitching()) {
Log_Write_Error(ERROR_SUBSYSTEM_GPS, ERROR_CODE_GPS_GLITCH);
}else{
Log_Write_Error(ERROR_SUBSYSTEM_GPS, ERROR_CODE_ERROR_RESOLVED);
}
AP_Notify::flags.gps_glitching = gps_glitch.glitching();
AP_Notify::flags.gps_glitching = report_gps_glitch;
}
}
}

View File

@ -185,7 +185,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
if (g.compass_enabled && compass.healthy() && ahrs.use_compass()) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
}
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS && !gps_glitch.glitching()) {
if (g_gps != NULL && g_gps->status() > GPS::NO_GPS && (!gps_glitch.glitching()||ap.usb_connected)) {
control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
}
if (ap.rc_receiver_present && !failsafe.radio) {