mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
Fix debug output of alt-hold data, accSum was reset prior to output.
This commit is contained in:
parent
596ac71861
commit
af87cff18f
1 changed files with 6 additions and 5 deletions
|
@ -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)
|
accAlt = accAlt * barometerConfig->baro_cf_alt + (float)BaroAlt * (1.0f - barometerConfig->baro_cf_alt); // complementary filter for Altitude estimation (baro & acc)
|
||||||
vel += vel_acc;
|
vel += vel_acc;
|
||||||
|
|
||||||
|
#if 1
|
||||||
|
debug[1] = accSum[2] / accSumCount; // acceleration
|
||||||
|
debug[2] = vel; // velocity
|
||||||
|
debug[3] = accAlt; // height
|
||||||
|
#endif
|
||||||
|
|
||||||
accSum_reset();
|
accSum_reset();
|
||||||
|
|
||||||
if (!isBaroCalibrationComplete()) {
|
if (!isBaroCalibrationComplete()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if 1
|
|
||||||
debug[1] = accSum[2] / accSumCount; // acceleration
|
|
||||||
debug[2] = vel; // velocity
|
|
||||||
debug[3] = accAlt; // height
|
|
||||||
#endif
|
|
||||||
|
|
||||||
EstAlt = accAlt;
|
EstAlt = accAlt;
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue