mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: ignore first ekf core switch
The ekf core is initialised to -1 but after initialisation changes to zero. Ignore this first change.
This commit is contained in:
parent
ec1462dccf
commit
26c3295042
@ -223,7 +223,7 @@ private:
|
||||
|
||||
// system time in milliseconds of last recorded yaw reset from ekf
|
||||
uint32_t ekfYawReset_ms = 0;
|
||||
uint8_t ekf_primary_core;
|
||||
int8_t ekf_primary_core;
|
||||
|
||||
// GCS selection
|
||||
AP_SerialManager serial_manager;
|
||||
|
@ -183,10 +183,10 @@ void Copter::check_ekf_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) {
|
||||
if ((EKF2.getPrimaryCoreIndex() != ekf_primary_core) && (EKF2.getPrimaryCoreIndex() != -1)) {
|
||||
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);
|
||||
gcs_send_text_fmt(MAV_SEVERITY_WARNING, "EKF primary changed:%d\n", (unsigned)ekf_primary_core);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user