1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Fix debug output of alt-hold data, accSum was reset prior to output.

This commit is contained in:
Dominic Clifton 2014-07-02 18:51:27 +01:00
parent 596ac71861
commit af87cff18f

View file

@ -439,17 +439,18 @@ void calculateEstimatedAltitude(uint32_t currentTime)
accAlt = accAlt * barometerConfig->baro_cf_alt + (float)BaroAlt * (1.0f - barometerConfig->baro_cf_alt); // complementary filter for Altitude estimation (baro & acc)
vel += vel_acc;
#if 1
debug[1] = accSum[2] / accSumCount; // acceleration
debug[2] = vel; // velocity
debug[3] = accAlt; // height
#endif
accSum_reset();
if (!isBaroCalibrationComplete()) {
return;
}
#if 1
debug[1] = accSum[2] / accSumCount; // acceleration
debug[2] = vel; // velocity
debug[3] = accAlt; // height
#endif
EstAlt = accAlt;