mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
HAL_PX4: fixed cork() for RCOutput
This commit is contained in:
parent
a80eea5de4
commit
c493ba81e4
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user