HAL_PX4: fixed cork() for RCOutput

This commit is contained in:
Andrew Tridgell 2016-10-12 08:02:41 +11:00
parent a80eea5de4
commit c493ba81e4
1 changed files with 1 additions and 1 deletions

View File

@ -539,7 +539,7 @@ void PX4RCOutput::push()
void PX4RCOutput::_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
* sent from push() */
_send_outputs();