mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_NavEKF : Use synthetic sideslip fusion during GPS denied operation with airspeed
This commit is contained in:
parent
35811758d7
commit
a24bfc1b8a
@ -739,10 +739,10 @@ void NavEKF::SelectBetaFusion()
|
|||||||
// Determine if synthetic sidelsip data should be fused
|
// Determine if synthetic sidelsip data should be fused
|
||||||
// synthetic sidelip fusion only works for fixed wing aircraft and relies on the average sideslip being close to zero
|
// synthetic sidelip fusion only works for fixed wing aircraft and relies on the average sideslip being close to zero
|
||||||
// it requires a stable wind estimate for best results and should not be used for aerobatic flight
|
// it requires a stable wind estimate for best results and should not be used for aerobatic flight
|
||||||
// we only fuse synthetic sideslip measurements if we are not using a compass, are not on the ground, enough time has
|
// we fuse synthetic sideslip measurements if:
|
||||||
// lapsed since our last fusion and we have not fused magnetometer data on this time step or the immediate fusion
|
// (we are not using a compass OR (we are dead-reckoning position AND using airspeed)) AND not on the ground AND enough time has lapsed since our last fusion AND
|
||||||
// flag is set
|
// (we have not fused magnetometer data on this time step OR the immediate fusion flag is set)
|
||||||
if (!use_compass() && !onGround && ((IMUmsec - BETAmsecPrev) >= _msecBetaAvg) && (!magFusePerformed || fuseMeNow)) {
|
if ((!use_compass() || (!posHealth && useAirspeed())) && !onGround && ((IMUmsec - BETAmsecPrev) >= _msecBetaAvg) && (!magFusePerformed || fuseMeNow)) {
|
||||||
FuseSideslip();
|
FuseSideslip();
|
||||||
BETAmsecPrev = IMUmsec;
|
BETAmsecPrev = IMUmsec;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user