From d16be50e57efe0106190119970c47f8fc9387033 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 4 Sep 2021 18:51:27 +0100 Subject: [PATCH] AP_Motors: add PWM min and max param conversion function --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 10 ++++++++++ libraries/AP_Motors/AP_MotorsMulticopter.h | 3 +++ 2 files changed, 13 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 1670f0924f..94864feda9 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -774,3 +774,13 @@ void AP_MotorsMulticopter::save_params_on_disarm() _throttle_hover.save(); } } + +// 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()) { + return; + } + _pwm_min.set_and_save(radio_min); + _pwm_max.set_and_save(radio_max); +} diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index dacc980980..b4e34447da 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -105,6 +105,9 @@ public: // return whether a motor is enabled or not bool is_motor_enabled(uint8_t i) override { return motor_enabled[i]; } + // convert values to PWM min and max if not configured + void convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max); + // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[];