APM_Control: lower default target filter frequencies

this will remove a lot of the level flight noise causing oscillation
at higher gains
This commit is contained in:
Andrew Tridgell 2021-04-14 08:02:11 +10:00
parent dd98f00947
commit bb1dc7192b
2 changed files with 2 additions and 2 deletions

View File

@ -53,7 +53,7 @@ private:
AP_Float _roll_ff;
uint32_t _last_t;
float _last_out;
AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 10, 7, 4, 0.02, 150, 1};
AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 1.5, 7, 4, 0.02, 150, 1};
float angle_err_deg;
AP_Logger::PID_Info _pid_info;

View File

@ -58,7 +58,7 @@ private:
bool failed_autotune_alloc;
uint32_t _last_t;
float _last_out;
AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 10, 7, 4, 0.02, 150, 1};
AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 3, 7, 4, 0.02, 150, 1};
float angle_err_deg;
AP_Logger::PID_Info _pid_info;