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

Explicitly use float literals in velocity calculation.

This commit is contained in:
Dominic Clifton 2014-06-24 00:30:58 +01:00
parent f127847bf2
commit 668772f1f3

View file

@ -461,7 +461,7 @@ void calculateEstimatedAltitude(uint32_t currentTime)
// apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity).
// By using CF it's possible to correct the drift of integrated accZ (velocity) without loosing the phase, i.e without delay
vel = vel * barometerConfig->baro_cf_vel + baroVel * (1 - barometerConfig->baro_cf_vel);
vel = vel * barometerConfig->baro_cf_vel + baroVel * (1.0f - barometerConfig->baro_cf_vel);
vel_tmp = lrintf(vel);
// set vario