mirror of https://github.com/ArduPilot/ardupilot
no longer using the raw pressure
This commit is contained in:
parent
6ecb6f21a6
commit
10330abf54
|
@ -1260,17 +1260,9 @@ static void update_altitude()
|
||||||
baro_alt = (baro_alt + read_barometer()) >> 1;
|
baro_alt = (baro_alt + read_barometer()) >> 1;
|
||||||
|
|
||||||
// calc the vertical accel rate
|
// calc the vertical accel rate
|
||||||
#if CLIMB_RATE_BARO == 0
|
int temp = (baro_alt - old_baro_alt) * 10;
|
||||||
int temp_baro_alt = (barometer._offset_press - barometer.RawPress) << 2; // invert and scale
|
baro_rate = (temp + baro_rate) >> 1;
|
||||||
temp_baro_alt = (float)temp_baro_alt * .1 + (float)old_baro_alt * .9;
|
|
||||||
|
|
||||||
baro_rate = (temp_baro_alt - old_baro_alt) * 10;
|
|
||||||
old_baro_alt = temp_baro_alt;
|
|
||||||
|
|
||||||
#else
|
|
||||||
baro_rate = (baro_alt - old_baro_alt) * 10;
|
|
||||||
old_baro_alt = baro_alt;
|
old_baro_alt = baro_alt;
|
||||||
#endif
|
|
||||||
|
|
||||||
// sonar_alt is calculaed in a faster loop and filtered with a mode filter
|
// sonar_alt is calculaed in a faster loop and filtered with a mode filter
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue