From b7db7f8cac297a026e1413270cea530df09137c0 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 4 Sep 2021 18:54:40 +0100 Subject: [PATCH] Sub: convert to PWM min and max in AP_Motors --- ArduSub/radio.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduSub/radio.cpp b/ArduSub/radio.cpp index a1495a799c..e79d4c7ac6 100644 --- a/ArduSub/radio.cpp +++ b/ArduSub/radio.cpp @@ -52,6 +52,7 @@ void Sub::init_rc_out() motors.set_update_rate(g.rc_speed); motors.set_loop_rate(scheduler.get_loop_rate_hz()); motors.init((AP_Motors::motor_frame_class)g.frame_configuration.get(), AP_Motors::motor_frame_type::MOTOR_FRAME_TYPE_PLUS); + motors.convert_pwm_min_max_param(channel_throttle->get_radio_min(), channel_throttle->get_radio_max()); motors.update_throttle_range(); // enable output to motors