HAL_VRBrain: fixed cork() for RCOutput

This commit is contained in:
Andrew Tridgell 2016-10-12 08:02:53 +11:00
parent c493ba81e4
commit 5530e3782d

View File

@ -546,7 +546,7 @@ void VRBRAINRCOutput::push()
void VRBRAINRCOutput::_timer_tick(void) void VRBRAINRCOutput::_timer_tick(void)
{ {
if (_output_mode != MODE_PWM_ONESHOT) { if (_output_mode != MODE_PWM_ONESHOT && !_corking) {
/* in oneshot mode the timer does nothing as the outputs are /* in oneshot mode the timer does nothing as the outputs are
* sent from push() */ * sent from push() */
_send_outputs(); _send_outputs();