mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: log EKF lane switch
This commit is contained in:
parent
35864c6226
commit
d74ae535d1
@ -223,6 +223,7 @@ private:
|
|||||||
|
|
||||||
// system time in milliseconds of last recorded yaw reset from ekf
|
// system time in milliseconds of last recorded yaw reset from ekf
|
||||||
uint32_t ekfYawReset_ms = 0;
|
uint32_t ekfYawReset_ms = 0;
|
||||||
|
uint8_t ekf_primary_core;
|
||||||
|
|
||||||
// GCS selection
|
// GCS selection
|
||||||
AP_SerialManager serial_manager;
|
AP_SerialManager serial_manager;
|
||||||
|
@ -407,6 +407,7 @@ enum DevOptions {
|
|||||||
#define ERROR_SUBSYSTEM_TERRAIN 21
|
#define ERROR_SUBSYSTEM_TERRAIN 21
|
||||||
#define ERROR_SUBSYSTEM_NAVIGATION 22
|
#define ERROR_SUBSYSTEM_NAVIGATION 22
|
||||||
#define ERROR_SUBSYSTEM_FAILSAFE_TERRAIN 23
|
#define ERROR_SUBSYSTEM_FAILSAFE_TERRAIN 23
|
||||||
|
#define ERROR_SUBSYSTEM_EKF_PRIMARY 24
|
||||||
// general error codes
|
// general error codes
|
||||||
#define ERROR_CODE_ERROR_RESOLVED 0
|
#define ERROR_CODE_ERROR_RESOLVED 0
|
||||||
#define ERROR_CODE_FAILED_TO_INITIALISE 1
|
#define ERROR_CODE_FAILED_TO_INITIALISE 1
|
||||||
|
@ -181,4 +181,12 @@ void Copter::check_ekf_reset()
|
|||||||
Log_Write_Event(DATA_EKF_YAW_RESET);
|
Log_Write_Event(DATA_EKF_YAW_RESET);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
// check for change in primary EKF (log only, AC_WPNav handles position target adjustment)
|
||||||
|
if (EKF2.getPrimaryCoreIndex() != ekf_primary_core) {
|
||||||
|
ekf_primary_core = EKF2.getPrimaryCoreIndex();
|
||||||
|
Log_Write_Error(ERROR_SUBSYSTEM_EKF_PRIMARY, ekf_primary_core);
|
||||||
|
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "EKF primary changed:%u\n", (unsigned)ekf_primary_core);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user