Skip to content

Commit

Permalink
Bug fix: absolute altitude before arming is now correct when using GP…
Browse files Browse the repository at this point in the history
…S and Baro
  • Loading branch information
TonyBlitWorks committed Mar 21, 2020
1 parent 9c3d460 commit 5209a83
Showing 1 changed file with 5 additions and 1 deletion.
6 changes: 5 additions & 1 deletion src/main/flight/position.c
Expand Up @@ -146,7 +146,11 @@ void calculateEstimatedAltitude(timeUs_t currentTimeUs)


if (haveGpsAlt && haveBaroAlt && positionConfig()->altSource == DEFAULT) {
estimatedAltitudeCm = gpsAlt * gpsTrust + baroAlt * (1 - gpsTrust);
if (ARMING_FLAG(ARMED)) {
estimatedAltitudeCm = gpsAlt * gpsTrust + baroAlt * (1 - gpsTrust);
} else {
estimatedAltitudeCm = gpsAlt; //absolute altitude is shown before arming, ignore baro
}
#ifdef USE_VARIO
// baro is a better source for vario, so ignore gpsVertSpeed
estimatedVario = calculateEstimatedVario(baroAlt, dTime);
Expand Down

0 comments on commit 5209a83

Please sign in to comment.