mirror of https://github.com/ArduPilot/ardupilot
HAL_VRBrain: fixed cork() for RCOutput
This commit is contained in:
parent
c493ba81e4
commit
5530e3782d
|
@ -546,7 +546,7 @@ void VRBRAINRCOutput::push()
|
|||
|
||||
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
|
||||
* sent from push() */
|
||||
_send_outputs();
|
||||
|
|
Loading…
Reference in New Issue