HAL_PX4: cope with nested cork/push

This commit is contained in:
Andrew Tridgell 2017-04-18 10:02:11 +10:00
parent 9b297ef5a1
commit 9bdb6838e6
1 changed files with 6 additions and 4 deletions

View File

@ -543,10 +543,12 @@ void PX4RCOutput::push()
hal.gpio->pinMode(55, HAL_GPIO_OUTPUT); hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
hal.gpio->write(55, 0); hal.gpio->write(55, 0);
#endif #endif
_corking = false; if (_corking) {
if (_output_mode == MODE_PWM_ONESHOT) { _corking = false;
// run timer immediately in oneshot mode if (_output_mode == MODE_PWM_ONESHOT) {
_send_outputs(); // run timer immediately in oneshot mode
_send_outputs();
}
} }
} }