return to prev climb rate calc

This commit is contained in:
Jason Short 2011-11-19 13:58:41 -08:00
parent 35524f6da7
commit 579096cd2e
1 changed files with 9 additions and 2 deletions

View File

@ -1244,13 +1244,20 @@ static void update_altitude()
#else
// This is real life
// read in Actual Baro Altitude
baro_alt = (baro_alt + read_barometer()) >> 1;
// calc the vertical accel rate
#if CLIMB_RATE_BARO = 1
int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 1; // invert and scale
baro_rate = (temp_baro_alt - old_baro_alt) * 10;
old_baro_alt = temp_baro_alt;
// read in Actual Baro Altitude
baro_alt = (baro_alt + read_barometer()) >> 1;
#else
baro_rate = (baro_alt - old_baro_alt) * 10;
old_baro_alt = baro_alt;
#endif
// sonar_alt is calculaed in a faster loop and filtered with a mode filter
#endif