APM_Control: remove unused variables

This commit is contained in:
Peter Barker 2021-08-18 20:34:35 +10:00 committed by Randy Mackay
parent 034f59e5b8
commit 066ad0f8da
2 changed files with 0 additions and 2 deletions

View File

@ -50,7 +50,6 @@ private:
bool failed_autotune_alloc;
AP_Int16 _max_rate_neg;
AP_Float _roll_ff;
uint32_t _last_t;
float _last_out;
AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 3, 0, 12, 0.02, 150, 1};
float angle_err_deg;

View File

@ -55,7 +55,6 @@ private:
AP_AutoTune::ATGains gains;
AP_AutoTune *autotune;
bool failed_autotune_alloc;
uint32_t _last_t;
float _last_out;
AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 3, 0, 12, 0.02, 150, 1};
float angle_err_deg;