From 18cab7a4147b3b487b039e8ac3b8e933b1cdc556 Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Fri, 28 Feb 2020 00:22:29 +0000 Subject: [PATCH] AP_Motors: MotorsMulticopter fix floating boost output --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index c957914697..1795818828 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -263,6 +263,8 @@ void AP_MotorsMulticopter::output_boost_throttle(void) if (_boost_scale > 0) { float throttle = constrain_float(get_throttle() * _boost_scale, 0, 1); SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, throttle * 1000); + } else { + SRV_Channels::set_output_scaled(SRV_Channel::k_boost_throttle, 0); } }