From ba389e339537fcd3a3d90ddd7ddc1f681160de16 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 a4927edf99..cb37d3e163 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -748,3 +748,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 2f32d33721..00ff010b2c 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -99,6 +99,9 @@ public: // as vectoring is used for yaw control virtual void disable_yaw_torque(void) {} + // 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[];