mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-28 19:48:31 -04:00
AP_Soaring: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
0da2d9f8eb
commit
705a885d82
@ -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)
|
||||
|
@ -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();
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user