Browse Source

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
master
Andrew Tridgell 8 years ago committed by Randy Mackay
parent
commit
787a2093ec
  1. 2
      libraries/AP_HAL_PX4/RCOutput.cpp

2
libraries/AP_HAL_PX4/RCOutput.cpp

@ -504,7 +504,7 @@ void PX4RCOutput::_send_outputs(void) @@ -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;

Loading…
Cancel
Save