mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: fixed non-contiguous motor outputs
this fixes tricopter with chan3 never set
This commit is contained in:
parent
05e9f360b2
commit
bcd0d48ced
|
@ -435,6 +435,8 @@ void PX4RCOutput::_send_outputs(void)
|
||||||
for (int i=to_send-1; i >= 0; i--) {
|
for (int i=to_send-1; i >= 0; i--) {
|
||||||
if (_period[i] == 0 || _period[i] == PWM_IGNORE_THIS_CHANNEL) {
|
if (_period[i] == 0 || _period[i] == PWM_IGNORE_THIS_CHANNEL) {
|
||||||
to_send = i;
|
to_send = i;
|
||||||
|
} else {
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue