HAL_PX4: work-around for periodic enable_ch() calls

This commit is contained in:
Holger Steinhaus 2014-08-27 18:28:30 +02:00 committed by Andrew Tridgell
parent e5549c90a1
commit 9e9c62d245
1 changed files with 3 additions and 1 deletions

View File

@ -149,7 +149,9 @@ void PX4RCOutput::enable_ch(uint8_t ch)
_init_alt_channels();
}
_enabled_channels |= (1U<<ch);
_period[ch] = 0;
if (_period[ch] == PWM_IGNORE_THIS_CHANNEL) {
_period[ch] = 0;
}
}
void PX4RCOutput::disable_ch(uint8_t ch)