From aafec1fbe73b6ce69f5625deeb52897d3ab9d154 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 12 May 2022 08:04:36 +1000 Subject: [PATCH] APM_Control: fixed use of configured() vs configured_in_storage() --- libraries/APM_Control/AP_PitchController.cpp | 2 +- libraries/APM_Control/AP_RollController.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 181ad2c65f..502d9d9f20 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -356,7 +356,7 @@ void AP_PitchController::reset_I() void AP_PitchController::convert_pid() { AP_Float &ff = rate_pid.ff(); - if (ff.configured_in_storage()) { + if (ff.configured()) { return; } diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 3e0a433b3b..799a9d3240 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -258,7 +258,7 @@ void AP_RollController::reset_I() void AP_RollController::convert_pid() { AP_Float &ff = rate_pid.ff(); - if (ff.configured_in_storage()) { + if (ff.configured()) { return; } float old_ff=0, old_p=1.0, old_i=0.3, old_d=0.08;