mirror of https://github.com/ArduPilot/ardupilot
AP_Soaring: make function const
This commit is contained in:
parent
8b8ca504fc
commit
52d9dc1471
|
@ -126,7 +126,7 @@ float Variometer::calculate_aircraft_sinkrate(float phi) const
|
|||
return _aspd_filt_constrained * (C1 + C2 / (cosphi * cosphi));
|
||||
}
|
||||
|
||||
float Variometer::calculate_circling_time_constant(float thermal_bank)
|
||||
float Variometer::calculate_circling_time_constant(float thermal_bank) const
|
||||
{
|
||||
// Calculate a time constant to use to filter quantities over a full thermal orbit.
|
||||
// This is used for rejecting variation in e.g. climb rate, or estimated climb rate
|
||||
|
|
|
@ -78,7 +78,7 @@ public:
|
|||
|
||||
float get_exp_thermalling_sink(void) const {return _expected_thermalling_sink;};
|
||||
|
||||
float calculate_circling_time_constant(const float thermal_bank);
|
||||
float calculate_circling_time_constant(const float thermal_bank) const;
|
||||
|
||||
private:
|
||||
const PolarParams &_polarParams;
|
||||
|
|
Loading…
Reference in New Issue