mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: cope with nested cork/push
This commit is contained in:
parent
9b297ef5a1
commit
9bdb6838e6
|
@ -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();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue