From bb1dc7192bfd58841518e8779e8df75c4ec4e459 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 14 Apr 2021 08:02:11 +1000 Subject: [PATCH] APM_Control: lower default target filter frequencies this will remove a lot of the level flight noise causing oscillation at higher gains --- libraries/APM_Control/AP_PitchController.h | 2 +- libraries/APM_Control/AP_RollController.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index bf172648d3..127530df66 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -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; diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 814bf2e63c..71df331c6a 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -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;