From ad8b9f58df4f7992b5784cd7cd02e0ec4c8b8c66 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Jul 2022 03:23:10 +0100 Subject: [PATCH] AP_Motors: use set and defualt --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 60c20d4b83..e7ee8631b6 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -517,8 +517,8 @@ void AP_MotorsMulticopter::update_throttle_range() // if all outputs are digital adjust the range. We also do this for type PWM_RANGE, as those use the // scaled output, which is then mapped to PWM via the SRV_Channel library if (SRV_Channels::have_digital_outputs(get_motor_mask()) || (_pwm_type == PWM_TYPE_PWM_RANGE)) { - _pwm_min = 1000; - _pwm_max = 2000; + _pwm_min.set_and_default(1000); + _pwm_max.set_and_default(2000); } hal.rcout->set_esc_scaling(get_pwm_output_min(), get_pwm_output_max());