mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
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:
parent
dd98f00947
commit
bb1dc7192b
@ -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;
|
||||
|
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user