mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF3: Fix bug preventing copter wind estimation at low speed
Also re-tunes process noise default for smoother wind velocity state estimates.
This commit is contained in:
parent
a829bc435c
commit
8744b0954f
|
@ -39,7 +39,7 @@
|
|||
#define FLOW_I_GATE_DEFAULT 300
|
||||
#define CHECK_SCALER_DEFAULT 100
|
||||
#define FLOW_USE_DEFAULT 1
|
||||
#define WIND_P_NSE_DEFAULT 1.0
|
||||
#define WIND_P_NSE_DEFAULT 0.5
|
||||
|
||||
#elif APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||
// rover defaults
|
||||
|
|
|
@ -66,7 +66,7 @@ void NavEKF3_core::setWindMagStateLearningMode()
|
|||
inhibitWindStates = true;
|
||||
updateStateIndexLim();
|
||||
} else if (inhibitWindStates && canEstimateWind &&
|
||||
sq(stateStruct.velocity.x) + sq(stateStruct.velocity.y) > sq(5.0f)) {
|
||||
(sq(stateStruct.velocity.x) + sq(stateStruct.velocity.y) > sq(5.0f) || dragFusionEnabled)) {
|
||||
inhibitWindStates = false;
|
||||
updateStateIndexLim();
|
||||
// set states and variances
|
||||
|
|
Loading…
Reference in New Issue