Browse Source

HAL_PX4: fixed non-contiguous motor outputs

this fixes tricopter with chan3 never set
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
bcd0d48ced
  1. 2
      libraries/AP_HAL_PX4/RCOutput.cpp

2
libraries/AP_HAL_PX4/RCOutput.cpp

@ -435,6 +435,8 @@ void PX4RCOutput::_send_outputs(void) @@ -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;
}
}
}

Loading…
Cancel
Save