mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
APM_Control: tweak tuning settings
This commit is contained in:
parent
ccd7b15d06
commit
7e64875a02
@ -295,9 +295,9 @@ void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler)
|
||||
old_FF*(1-AUTOTUNE_DECREASE_FF_STEP*0.01),
|
||||
old_FF*(1+AUTOTUNE_INCREASE_FF_STEP*0.01));
|
||||
|
||||
// did the P or D components go over 15% of total actuator?
|
||||
// did the P or D components go over 30% of total actuator?
|
||||
const float abs_actuator = MAX(max_actuator, fabsf(min_actuator));
|
||||
const float PD_high = 0.15 * abs_actuator;
|
||||
const float PD_high = 0.3 * abs_actuator;
|
||||
bool PD_significant = (max_P > PD_high || max_D > PD_high);
|
||||
|
||||
// see if we overshot
|
||||
|
@ -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, 100, 1};
|
||||
AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 10, 7, 4, 0.02, 150, 1};
|
||||
|
||||
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, 100, 1};
|
||||
AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 10, 7, 4, 0.02, 150, 1};
|
||||
|
||||
AP_Logger::PID_Info _pid_info;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user