mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: force first EKF lane when disarmed
this ensures we consistently fly with EKF lane1 if it is healthy at the point we arm. Otherwise the choice of lane will be a lottery. This is important as many systems have quite different filtering and vibration characteristics on their different IMUs. We by default enable fast sampling only on the first IMU for example, which means the 2nd and 3rd IMUs are more vulnerable to high freq causing aliasing.
This commit is contained in:
parent
bf11746da5
commit
567c902e75
|
@ -766,6 +766,18 @@ void NavEKF2::UpdateFilter(void)
|
|||
}
|
||||
}
|
||||
|
||||
if (primary != 0 && core[0].healthy() && !hal.util->get_soft_armed()) {
|
||||
// when on the ground and disarmed force the first lane. This
|
||||
// avoids us ending with with a lottery for which IMU is used
|
||||
// in each flight. Otherwise the alignment of the timing of
|
||||
// the lane updates with the timing of GPS updates can lead to
|
||||
// a lane other than the first one being used as primary for
|
||||
// some flights. As different IMUs may have quite different
|
||||
// noise characteristics this leads to inconsistent
|
||||
// performance
|
||||
primary = 0;
|
||||
}
|
||||
|
||||
check_log_write();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue