From b2e43d1dee2c5071cdb4d9b38de00988875f1dec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 12 May 2022 07:49:58 +1000 Subject: [PATCH] AP_Motors: fixed override of MOT_PWM_MIN/MAX in defaults.parm need to check configured() not configured_in_storage() --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index e2ac056fdd..f389520884 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -794,7 +794,7 @@ void AP_MotorsMulticopter::save_params_on_disarm() // convert to PWM min and max in the motor lib void AP_MotorsMulticopter::convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max) { - if (_pwm_min.configured_in_storage() || _pwm_max.configured_in_storage()) { + if (_pwm_min.configured() || _pwm_max.configured()) { return; } _pwm_min.set_and_save(radio_min);