AP_NavEKF: Add missing GPs check report

This commit is contained in:
Paul Riseborough 2015-10-09 01:25:13 -07:00 committed by Randy Mackay
parent a3a1dabb94
commit f451a81ef9
3 changed files with 15 additions and 9 deletions

View File

@ -4950,15 +4950,16 @@ void NavEKF::getFilterGpsStatus(nav_gps_status &faults) const
faults.value = 0;
// set individual flags
faults.flags.bad_sAcc = gpsCheckStatus.bad_sAcc; // reported speed accuracy is insufficient
faults.flags.bad_hAcc = gpsCheckStatus.bad_hAcc; // reported horizontal position accuracy is insufficient
faults.flags.bad_yaw = gpsCheckStatus.bad_yaw; // EKF heading accuracy is too large for GPS use
faults.flags.bad_sats = gpsCheckStatus.bad_sats; // reported number of satellites is insufficient
faults.flags.bad_VZ = gpsCheckStatus.bad_VZ; // GPS vertical velocity is inconsistent with the IMU and Baro measurements
faults.flags.bad_horiz_drift = gpsCheckStatus.bad_horiz_drift; // GPS horizontal drift is too large to start using GPS (check assumes vehicle is static)
faults.flags.bad_hdop = gpsCheckStatus.bad_hdop; // reported HDoP is too large to start using GPS
faults.flags.bad_vert_vel = gpsCheckStatus.bad_vert_vel; // GPS vertical speed is too large to start using GPS (check assumes vehicle is static)
faults.flags.bad_fix = gpsCheckStatus.bad_fix; // The GPS cannot provide the 3D fix required
faults.flags.bad_sAcc = gpsCheckStatus.bad_sAcc; // reported speed accuracy is insufficient
faults.flags.bad_hAcc = gpsCheckStatus.bad_hAcc; // reported horizontal position accuracy is insufficient
faults.flags.bad_yaw = gpsCheckStatus.bad_yaw; // EKF heading accuracy is too large for GPS use
faults.flags.bad_sats = gpsCheckStatus.bad_sats; // reported number of satellites is insufficient
faults.flags.bad_VZ = gpsCheckStatus.bad_VZ; // GPS vertical velocity is inconsistent with the IMU and Baro measurements
faults.flags.bad_horiz_drift = gpsCheckStatus.bad_horiz_drift; // GPS horizontal drift is too large to start using GPS (check assumes vehicle is static)
faults.flags.bad_hdop = gpsCheckStatus.bad_hdop; // reported HDoP is too large to start using GPS
faults.flags.bad_vert_vel = gpsCheckStatus.bad_vert_vel; // GPS vertical speed is too large to start using GPS (check assumes vehicle is static)
faults.flags.bad_fix = gpsCheckStatus.bad_fix; // The GPS cannot provide the 3D fix required
faults.flags.bad_horiz_vel = gpsCheckStatus.bad_horiz_vel; // The GPS horizontal speed is excessive (check assumes the vehicle is static)
}
/*
@ -5413,6 +5414,9 @@ bool NavEKF::calcGpsGoodToAlign(void)
hal.util->snprintf(prearm_fail_string,
sizeof(prearm_fail_string),
"GPS horizontal speed %.2fm/s (needs 0.30)", (double)gpsDriftNE);
gpsCheckStatus.bad_horiz_vel = true;
} else {
gpsCheckStatus.bad_horiz_vel = false;
}
// return healthy if we already have an origin and are inflight to prevent a race condition when checking the status on the ground after landing

View File

@ -847,6 +847,7 @@ private:
bool bad_hdop:1;
bool bad_vert_vel:1;
bool bad_fix:1;
bool bad_horiz_vel:1;
} gpsCheckStatus;
// states held by magnetomter fusion across time steps

View File

@ -51,6 +51,7 @@ union nav_gps_status {
uint16_t bad_hdop : 1; // 6 - true if the reported HDoP is insufficient to start using GPS
uint16_t bad_vert_vel : 1; // 7 - true if the GPS vertical speed is too large to start using GPS (this check assumes vehicle is static)
uint16_t bad_fix : 1; // 8 - true if the GPS is not providing a 3D fix
uint16_t bad_horiz_vel : 1; // 9 - true if the GPS horizontal speed is excessive (this check assumes the vehicle is static)
} flags;
uint16_t value;
};