mirror of https://github.com/ArduPilot/ardupilot
APM_Control: adjust fixed wing filter defaults
adjust defaults based on discussions with Paul, and initialise the FLTT value based on the controller time constant
This commit is contained in:
parent
07acfd49b2
commit
3b64d41408
|
@ -373,6 +373,9 @@ void AP_AutoTune::update(AP_Logger::PID_Info &pinfo, float scaler, float angle_e
|
|||
rpid.kD().set(D);
|
||||
rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST)));
|
||||
|
||||
// setup target filter to be suitable for time constant
|
||||
rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI));
|
||||
|
||||
current.FF = FF;
|
||||
current.P = P;
|
||||
current.I = rpid.kI().get();
|
||||
|
@ -473,6 +476,7 @@ void AP_AutoTune::save_gains(const ATGains &v)
|
|||
save_float_if_changed(rpid.kI(), v.I);
|
||||
save_float_if_changed(rpid.kD(), v.D);
|
||||
save_float_if_changed(rpid.kIMAX(), v.IMAX);
|
||||
save_float_if_changed(rpid.filt_T_hz(), v.flt_T);
|
||||
last_save = get_gains(current);
|
||||
current = tmp;
|
||||
}
|
||||
|
@ -488,6 +492,7 @@ AP_AutoTune::ATGains AP_AutoTune::get_gains(const ATGains &v)
|
|||
ret.I = rpid.kI();
|
||||
ret.D = rpid.kD();
|
||||
ret.IMAX = rpid.kIMAX();
|
||||
ret.flt_T = rpid.filt_T_hz();
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -502,6 +507,7 @@ void AP_AutoTune::set_gains(const ATGains &v)
|
|||
rpid.kI().set(v.I);
|
||||
rpid.kD().set(v.D);
|
||||
rpid.kIMAX().set(v.IMAX);
|
||||
rpid.filt_T_hz().set(v.flt_T);
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -12,7 +12,7 @@ public:
|
|||
AP_Float tau;
|
||||
AP_Int16 rmax_pos;
|
||||
AP_Int16 rmax_neg;
|
||||
float FF, P, I, D, IMAX;
|
||||
float FF, P, I, D, IMAX, flt_T;
|
||||
};
|
||||
|
||||
enum ATType {
|
||||
|
|
|
@ -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, 1.5, 7, 4, 0.02, 150, 1};
|
||||
AC_PID rate_pid{0.04, 0.15, 0, 0.345, 0.666, 3, 0, 12, 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, 3, 7, 4, 0.02, 150, 1};
|
||||
AC_PID rate_pid{0.08, 0.15, 0, 0.345, 0.666, 3, 0, 12, 0.02, 150, 1};
|
||||
float angle_err_deg;
|
||||
|
||||
AP_Logger::PID_Info _pid_info;
|
||||
|
|
Loading…
Reference in New Issue