this fixes tricopter with chan3 never set
@ -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;
}