mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_PX4: if there are no enabled channels don't send to PX4IO
this makes it possible to disable PWM output to IO to test override
This commit is contained in:
parent
16fd113020
commit
e22c8b27a9
@ -243,6 +243,11 @@ void PX4RCOutput::_timer_tick(void)
|
||||
{
|
||||
uint32_t now = hal.scheduler->micros();
|
||||
|
||||
if ((_enabled_channels & ((1U<<_servo_count)-1)) == 0) {
|
||||
// no channels enabled
|
||||
goto update_pwm;
|
||||
}
|
||||
|
||||
// always send at least at 20Hz, otherwise the IO board may think
|
||||
// we are dead
|
||||
if (now - _last_output > 50000) {
|
||||
|
Loading…
Reference in New Issue
Block a user