Copter: adjust yaw imbalance check to only check imax rather than i

Existing code was causing way too many false-positives
This commit is contained in:
Andrew Tridgell 2021-05-27 07:50:18 +10:00 committed by Peter Barker
parent 8701932670
commit acb70abe86

View File

@ -14,7 +14,6 @@
// Yaw imbalance check
#define YAW_IMBALANCE_IMAX_THRESHOLD 0.75f
#define YAW_IMBALANCE_I_THERSHOLD 0.1f
#define YAW_IMBALANCE_WARN_MS 10000
// crash_check - disarms motors if a crash has been detected
@ -209,8 +208,7 @@ void Copter::yaw_imbalance_check()
}
const float I_max = attitude_control->get_rate_yaw_pid().imax();
if ((is_positive(I_max) && ((I > YAW_IMBALANCE_IMAX_THRESHOLD * I_max) || (is_equal(I_term,I_max)))) ||
(I >YAW_IMBALANCE_I_THERSHOLD)) {
if ((is_positive(I_max) && ((I > YAW_IMBALANCE_IMAX_THRESHOLD * I_max) || (is_equal(I_term,I_max))))) {
// filtered using over precentage of I max or unfiltered = I max
// I makes up more than precentage of total available control power
const uint32_t now = millis();