mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 12:25:20 +03:00
Whitespace/compiler warnings cleanups by Dominic Clifton;
Slight tweak of new althold defaults NOT-flight-tested .hex committing so people can commence with althold testing. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@391 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
77a241bd5f
commit
509e349e69
11 changed files with 3312 additions and 3231 deletions
|
@ -372,7 +372,6 @@ int getEstimatedAltitude(void)
|
|||
int32_t baroVel;
|
||||
int32_t vel_tmp;
|
||||
int32_t BaroAlt_tmp;
|
||||
float vel_calc;
|
||||
static float vel = 0.0f;
|
||||
static float accAlt = 0.0f;
|
||||
static int32_t lastBaroAlt;
|
||||
|
@ -396,8 +395,7 @@ int getEstimatedAltitude(void)
|
|||
BaroAlt = BaroAlt * cfg.baro_noise_lpf + BaroAlt_tmp * (1.0f - cfg.baro_noise_lpf); // additional LPF to reduce baro noise
|
||||
|
||||
// Integrator - velocity, cm/sec
|
||||
vel_calc = (float) accSum[2] * accVelScale * (float) accTimeSum / (float) accSumCount;
|
||||
vel += vel_calc;
|
||||
vel += (float)accSum[2] * accVelScale * (float)accTimeSum / (float)accSumCount;
|
||||
|
||||
// Integrator - Altitude in cm
|
||||
accAlt += vel * ((float) accTimeSum * 0.0000005f); // integrate velocity to get distance (x= a/2 * t^2)
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue