From 3f765d8bbed07af403439bae63bec11b1fa58116 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jul 2019 11:27:28 +1000 Subject: [PATCH] APM_Control: added decay_I() function used by VTOL planes to decay integrator on fixed wing components when at very low airspeed --- libraries/APM_Control/AP_PitchController.h | 8 ++++++++ libraries/APM_Control/AP_RollController.h | 8 ++++++++ libraries/APM_Control/AP_YawController.h | 10 +++++++++- 3 files changed, 25 insertions(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index e3334416b3..dd2d6eb602 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -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(); } diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 7b243be8e2..9b317f1073 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -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(); } diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index 09edd6daf7..426fcbbbbe 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -26,7 +26,15 @@ public: void reset_I(); - const DataFlash_Class::PID_Info& get_pid_info(void) const {return _pid_info; } + const DataFlash_Class::PID_Info& get_pid_info(void) const {return _pid_info; } + + /* + 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; + } static const struct AP_Param::GroupInfo var_info[];