mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
return to prev climb rate calc
This commit is contained in:
parent
35524f6da7
commit
579096cd2e
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user