From bcd0d48cedc28ee987606e054bb28291175ee599 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 22 Apr 2016 11:51:08 +1000 Subject: [PATCH] HAL_PX4: fixed non-contiguous motor outputs this fixes tricopter with chan3 never set --- libraries/AP_HAL_PX4/RCOutput.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 2ad060219b..94c919de95 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -435,6 +435,8 @@ void PX4RCOutput::_send_outputs(void) for (int i=to_send-1; i >= 0; i--) { if (_period[i] == 0 || _period[i] == PWM_IGNORE_THIS_CHANNEL) { to_send = i; + } else { + break; } } }