Browse Source

Baro: make get_altitude_difference const

master
Randy Mackay 11 years ago
parent
commit
e9fbea9497
  1. 2
      libraries/AP_Baro/AP_Baro.cpp
  2. 2
      libraries/AP_Baro/AP_Baro.h

2
libraries/AP_Baro/AP_Baro.cpp

@ -132,7 +132,7 @@ void AP_Baro::update_calibration() @@ -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

2
libraries/AP_Baro/AP_Baro.h

@ -43,7 +43,7 @@ public: @@ -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);

Loading…
Cancel
Save