diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index e4f40da04f..fe2e35d389 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -132,7 +132,7 @@ void AP_Baro::update_calibration() // return altitude difference in meters between current pressure and a // given base_pressure in Pascal -float AP_Baro::get_altitude_difference(float base_pressure, float pressure) +float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const { float ret; #if HAL_CPU_CLASS <= HAL_CPU_CLASS_16 diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index c1d49a9f37..684260a758 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -43,7 +43,7 @@ public: // get altitude difference in meters relative given a base // pressure in Pascal - float get_altitude_difference(float base_pressure, float pressure); + float get_altitude_difference(float base_pressure, float pressure) const; // get scale factor required to convert equivalent to true airspeed float get_EAS2TAS(void);