Browse Source

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
master
Andrew Tridgell 10 years ago
parent
commit
e22c8b27a9
  1. 5
      libraries/AP_HAL_PX4/RCOutput.cpp

5
libraries/AP_HAL_PX4/RCOutput.cpp

@ -243,6 +243,11 @@ void PX4RCOutput::_timer_tick(void) @@ -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…
Cancel
Save