mirror of https://github.com/ArduPilot/ardupilot
AP_Soaring: remove unused variables
This commit is contained in:
parent
914316a529
commit
4bbf623cac
|
@ -55,7 +55,6 @@ class SoaringController {
|
|||
float McCready(float alt);
|
||||
|
||||
float _thermalability;
|
||||
float _expected_sink;
|
||||
|
||||
LowPassFilter<float> _position_x_filter;
|
||||
LowPassFilter<float> _position_y_filter;
|
||||
|
@ -148,4 +147,4 @@ private:
|
|||
bool _exit_commanded;
|
||||
};
|
||||
|
||||
#endif // HAL_SOARING_ENABLED
|
||||
#endif // HAL_SOARING_ENABLED
|
||||
|
|
|
@ -21,14 +21,9 @@ class Variometer {
|
|||
// store time of last update
|
||||
uint64_t _prev_update_time;
|
||||
|
||||
float _last_alt;
|
||||
|
||||
float _aspd_filt;
|
||||
float _aspd_filt_constrained;
|
||||
|
||||
float _last_aspd;
|
||||
float _last_roll;
|
||||
float _last_total_E;
|
||||
float _expected_thermalling_sink;
|
||||
|
||||
// declares a 5point average filter using floats
|
||||
|
|
Loading…
Reference in New Issue