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:
Andrew Tridgell 2014-11-06 17:29:14 +11:00
parent 16fd113020
commit e22c8b27a9

View File

@ -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) {