From 705a885d8293ccdfdcdad93392201429c0b7cee4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Mon, 1 Feb 2021 13:26:34 -0300 Subject: [PATCH] AP_Soaring: Add missing const in member functions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- libraries/AP_Soaring/Variometer.cpp | 2 +- libraries/AP_Soaring/Variometer.h | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 112e4b8a6b..916998fc8a 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -110,7 +110,7 @@ void Variometer::update(const float polar_K, const float polar_Cd0, const float float Variometer::calculate_aircraft_sinkrate(float phi, const float polar_K, const float polar_CD0, - const float polar_B) + const float polar_B) const { // Remove aircraft sink rate float CL0; // CL0 = 2*W/(rho*S*V^2) diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index 632fb1f818..c396973fef 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -47,13 +47,13 @@ public: float tau; void update(const float polar_K, const float polar_CD0, const float polar_B); - float calculate_aircraft_sinkrate(float phi, const float polar_K, const float polar_CD0, const float polar_B); + float calculate_aircraft_sinkrate(float phi, const float polar_K, const float polar_CD0, const float polar_B) const; void reset_filter(float value) { _climb_filter.reset(value);} - float get_airspeed(void) {return _aspd_filt;}; + float get_airspeed(void) const {return _aspd_filt;}; - float get_exp_thermalling_sink(void) {return _expected_thermalling_sink;}; + float get_exp_thermalling_sink(void) const {return _expected_thermalling_sink;}; float calculate_circling_time_constant(); };