mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
AP_NavEKF: fixed bug in flag reset for hgt fusion
This commit is contained in:
parent
2f3b2a7111
commit
b6b0c2a489
@ -274,6 +274,7 @@ void NavEKF::SelectVelPosFusion()
|
|||||||
{
|
{
|
||||||
FuseVelPosNED();
|
FuseVelPosNED();
|
||||||
newDataGps = false;
|
newDataGps = false;
|
||||||
|
newDataHgt = false;
|
||||||
posVelFuseStep = true;
|
posVelFuseStep = true;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
Loading…
Reference in New Issue
Block a user