AP_Soaring: make PolarParams const reference
This commit is contained in:
parent
f76d6ea739
commit
8b8ca504fc
@ -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);
|
||||
|
||||
|
@ -6,7 +6,7 @@ Manages the estimation of aircraft total energy, drag and vertical air velocity.
|
||||
|
||||
#include <AP_Logger/AP_Logger.h>
|
||||
|
||||
Variometer::Variometer(const AP_Vehicle::FixedWing &parms, PolarParams &polarParams) :
|
||||
Variometer::Variometer(const AP_Vehicle::FixedWing &parms, const PolarParams &polarParams) :
|
||||
_aparm(parms),
|
||||
_polarParams(polarParams)
|
||||
{
|
||||
|
@ -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;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user