From 787a2093ec577f602283b3a151e6d24360893468 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 1 Feb 2017 20:43:23 +1100 Subject: [PATCH] HAL_PX4: fixed motor test for brushed motors this fixes zero pwm output on a subset of channels. When using motortest and asking for a single channel, multiple channels fired due to an incorrect optimisation --- libraries/AP_HAL_PX4/RCOutput.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 711a314ef5..6795747b1c 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -504,7 +504,7 @@ void PX4RCOutput::_send_outputs(void) } if (to_send > 0) { for (int i=to_send-1; i >= 0; i--) { - if (_period[i] == 0 || _period[i] == PWM_IGNORE_THIS_CHANNEL) { + if (_period[i] == PWM_IGNORE_THIS_CHANNEL) { to_send = i; } else { break;