5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-05 15:38:29 -04:00

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
This commit is contained in:
Andrew Tridgell 2017-02-01 20:43:23 +11:00 committed by Randy Mackay
parent 2165a8832b
commit 787a2093ec

View File

@ -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;