mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: rename EKF check's error message to dataflash
It checks more than the compass so the old error message was misleading.
This commit is contained in:
parent
5d4e019397
commit
4723ed5e6e
@ -375,8 +375,8 @@ enum FlipState {
|
||||
// parachute failed to deploy because of low altitude
|
||||
#define ERROR_CODE_PARACHUTE_TOO_LOW 2
|
||||
// EKF check definitions
|
||||
#define ERROR_CODE_EKF_CHECK_BAD_COMPASS 2
|
||||
#define ERROR_CODE_EKF_CHECK_BAD_COMPASS_CLEARED 0
|
||||
#define ERROR_CODE_EKF_CHECK_BAD_VARIANCE 2
|
||||
#define ERROR_CODE_EKF_CHECK_BAD_VARIANCE_CLEARED 0
|
||||
// Baro specific error codes
|
||||
#define ERROR_CODE_BARO_GLITCH 2
|
||||
|
||||
|
@ -76,7 +76,7 @@ void ekf_check()
|
||||
ekf_check_state.fail_count_compass = EKF_CHECK_ITERATIONS_MAX;
|
||||
ekf_check_state.bad_compass = true;
|
||||
// log an error in the dataflash
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_EKF_CHECK, ERROR_CODE_EKF_CHECK_BAD_COMPASS);
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_EKF_CHECK, ERROR_CODE_EKF_CHECK_BAD_VARIANCE);
|
||||
// send message to gcs
|
||||
if ((hal.scheduler->millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("EKF variance"));
|
||||
@ -94,7 +94,7 @@ void ekf_check()
|
||||
if (ekf_check_state.fail_count_compass == 0) {
|
||||
ekf_check_state.bad_compass = false;
|
||||
// log recovery in the dataflash
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_EKF_CHECK, ERROR_CODE_EKF_CHECK_BAD_COMPASS_CLEARED);
|
||||
Log_Write_Error(ERROR_SUBSYSTEM_EKF_CHECK, ERROR_CODE_EKF_CHECK_BAD_VARIANCE_CLEARED);
|
||||
// clear failsafe
|
||||
failsafe_ekf_off_event();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user