mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_PX4: cope with nested cork/push
This commit is contained in:
parent
9b297ef5a1
commit
9bdb6838e6
@ -543,12 +543,14 @@ void PX4RCOutput::push()
|
||||
hal.gpio->pinMode(55, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(55, 0);
|
||||
#endif
|
||||
if (_corking) {
|
||||
_corking = false;
|
||||
if (_output_mode == MODE_PWM_ONESHOT) {
|
||||
// run timer immediately in oneshot mode
|
||||
_send_outputs();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void PX4RCOutput::timer_tick(void)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user