mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Baro: use fabs() not abs()
thanks to Randy for spotting this
This commit is contained in:
parent
31e1b7fcf6
commit
5607c89df0
@ -148,7 +148,7 @@ float AP_Baro::get_altitude(void)
|
||||
// assumes standard atmosphere lapse rate
|
||||
float AP_Baro::get_EAS2TAS(void)
|
||||
{
|
||||
if ((abs(_altitude - _last_altitude_EAS2TAS) < 100.0f) && (_EAS2TAS != 0.0f)) {
|
||||
if ((fabs(_altitude - _last_altitude_EAS2TAS) < 100.0f) && (_EAS2TAS != 0.0f)) {
|
||||
// not enough change to require re-calculating
|
||||
return _EAS2TAS;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user