From 8b8ca504fc9c1fa42f86a906cbea0346071c256f Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 14 Jul 2022 18:22:11 +0200 Subject: [PATCH] AP_Soaring: make PolarParams const reference --- libraries/AP_Soaring/SpeedToFly.h | 4 ++-- libraries/AP_Soaring/Variometer.cpp | 2 +- libraries/AP_Soaring/Variometer.h | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Soaring/SpeedToFly.h b/libraries/AP_Soaring/SpeedToFly.h index 526653a043..a433e82157 100644 --- a/libraries/AP_Soaring/SpeedToFly.h +++ b/libraries/AP_Soaring/SpeedToFly.h @@ -11,10 +11,10 @@ class SpeedToFly { float _CL_estimate = -1.0f; - Variometer::PolarParams &_polarParams; + const Variometer::PolarParams &_polarParams; public: - SpeedToFly(Variometer::PolarParams &polarParams) :_polarParams(polarParams) {} + SpeedToFly(const Variometer::PolarParams &polarParams) :_polarParams(polarParams) {} void update(float Wx, float Wz, float Wexp, float CLmin, float CLmax); diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 408652d220..9cf95179d9 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -6,7 +6,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity. #include -Variometer::Variometer(const AP_Vehicle::FixedWing &parms, PolarParams &polarParams) : +Variometer::Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams) : _aparm(parms), _polarParams(polarParams) { diff --git a/libraries/AP_Soaring/Variometer.h b/libraries/AP_Soaring/Variometer.h index 3f0ae2653b..c8abb1193e 100644 --- a/libraries/AP_Soaring/Variometer.h +++ b/libraries/AP_Soaring/Variometer.h @@ -53,7 +53,7 @@ public: AP_Float B; }; - Variometer(const AP_Vehicle::FixedWing &parms, PolarParams &polarParams); + Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams); float alt; float reading; @@ -81,6 +81,6 @@ public: float calculate_circling_time_constant(const float thermal_bank); private: - PolarParams &_polarParams; + const PolarParams &_polarParams; };