mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_NavEKF2: Prevent unwanted core switch on startup
Require primary core to be healthy for 10 seconds before starting selection logic
This commit is contained in:
parent
eaaea86843
commit
65ffe9d760
@ -523,7 +523,8 @@ NavEKF2::NavEKF2(const AP_AHRS *ahrs, AP_Baro &baro, const RangeFinder &rng) :
|
|||||||
gndEffectTimeout_ms(1000), // time in msec that baro ground effect compensation will timeout after initiation
|
gndEffectTimeout_ms(1000), // time in msec that baro ground effect compensation will timeout after initiation
|
||||||
gndEffectBaroScaler(4.0f), // scaler applied to the barometer observation variance when operating in ground effect
|
gndEffectBaroScaler(4.0f), // scaler applied to the barometer observation variance when operating in ground effect
|
||||||
gndGradientSigma(50), // RMS terrain gradient percentage assumed by the terrain height estimation
|
gndGradientSigma(50), // RMS terrain gradient percentage assumed by the terrain height estimation
|
||||||
fusionTimeStep_ms(10) // The minimum number of msec between covariance prediction and fusion operations
|
fusionTimeStep_ms(10), // The minimum number of msec between covariance prediction and fusion operations
|
||||||
|
runCoreSelection(false) // true when the default primary core has stabilised after startup and core selection can run
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
}
|
}
|
||||||
@ -658,8 +659,17 @@ void NavEKF2::UpdateFilter(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// If the current core selected has a bad error score or is unhealthy, switch to a healthy core with the lowest fault score
|
// If the current core selected has a bad error score or is unhealthy, switch to a healthy core with the lowest fault score
|
||||||
|
// Don't start running the check until the primary core has started returned healthy for at least 10 seconds to avoid switching
|
||||||
|
// due to initial alignment fluctuations and race conditions
|
||||||
|
if (!runCoreSelection) {
|
||||||
|
static uint64_t lastUnhealthyTime_us = 0;
|
||||||
|
if (!core[primary].healthy() || lastUnhealthyTime_us == 0) {
|
||||||
|
lastUnhealthyTime_us = imuSampleTime_us;
|
||||||
|
}
|
||||||
|
runCoreSelection = (imuSampleTime_us - lastUnhealthyTime_us) > 1E7;
|
||||||
|
}
|
||||||
float primaryErrorScore = core[primary].errorScore();
|
float primaryErrorScore = core[primary].errorScore();
|
||||||
if (primaryErrorScore > 1.0f || !core[primary].healthy()) {
|
if ((primaryErrorScore > 1.0f || !core[primary].healthy()) && runCoreSelection) {
|
||||||
float lowestErrorScore = 0.67f * primaryErrorScore;
|
float lowestErrorScore = 0.67f * primaryErrorScore;
|
||||||
uint8_t newPrimaryIndex = primary; // index for new primary
|
uint8_t newPrimaryIndex = primary; // index for new primary
|
||||||
for (uint8_t coreIndex=0; coreIndex<num_cores; coreIndex++) {
|
for (uint8_t coreIndex=0; coreIndex<num_cores; coreIndex++) {
|
||||||
|
@ -405,6 +405,8 @@ private:
|
|||||||
float core_delta; // the amount of D position change between cores when a change happened
|
float core_delta; // the amount of D position change between cores when a change happened
|
||||||
} pos_down_reset_data;
|
} pos_down_reset_data;
|
||||||
|
|
||||||
|
bool runCoreSelection; // true when the primary core has stabilised and the core selection logic can be started
|
||||||
|
|
||||||
// update the yaw reset data to capture changes due to a lane switch
|
// update the yaw reset data to capture changes due to a lane switch
|
||||||
// new_primary - index of the ekf instance that we are about to switch to as the primary
|
// new_primary - index of the ekf instance that we are about to switch to as the primary
|
||||||
// old_primary - index of the ekf instance that we are currently using as the primary
|
// old_primary - index of the ekf instance that we are currently using as the primary
|
||||||
|
Loading…
Reference in New Issue
Block a user