APM_Control: added decay_I() function

used by VTOL planes to decay integrator on fixed wing components when
at very low airspeed
This commit is contained in:
Andrew Tridgell 2019-07-07 11:20:49 +10:00
parent ebe2278f5d
commit 05bd0cb9f4
3 changed files with 24 additions and 0 deletions

View File

@ -26,6 +26,14 @@ public:
void reset_I();
/*
reduce the integrator, used when we have a low scale factor in a quadplane hover
*/
void decay_I() {
// this reduces integrator by 95% over 2s
_pid_info.I *= 0.995f;
}
void autotune_start(void) { autotune.start(); }
void autotune_restore(void) { autotune.stop(); }

View File

@ -26,6 +26,14 @@ public:
void reset_I();
/*
reduce the integrator, used when we have a low scale factor in a quadplane hover
*/
void decay_I() {
// this reduces integrator by 95% over 2s
_pid_info.I *= 0.995f;
}
void autotune_start(void) { autotune.start(); }
void autotune_restore(void) { autotune.stop(); }

View File

@ -26,6 +26,14 @@ public:
void reset_I();
/*
reduce the integrator, used when we have a low scale factor in a quadplane hover
*/
void decay_I() {
// this reduces integrator by 95% over 2s
_pid_info.I *= 0.995f;
}
const AP_Logger::PID_Info& get_pid_info(void) const {return _pid_info; }
static const struct AP_Param::GroupInfo var_info[];