mirror of https://github.com/ArduPilot/ardupilot
AP_Periph: fixed airspeed to use corrected pressure
this prevents the AP_Periph node from doing the fabs()
This commit is contained in:
parent
0f6f684bab
commit
318d467ecc
|
@ -1518,7 +1518,7 @@ void AP_Periph_FW::can_airspeed_update(void)
|
|||
// don't send any data
|
||||
return;
|
||||
}
|
||||
const float press = airspeed.get_differential_pressure();
|
||||
const float press = airspeed.get_corrected_pressure();
|
||||
float temp;
|
||||
if (!airspeed.get_temperature(temp)) {
|
||||
temp = nanf("");
|
||||
|
|
Loading…
Reference in New Issue