mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: work-around for periodic enable_ch() calls
This commit is contained in:
parent
e5549c90a1
commit
9e9c62d245
|
@ -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)
|
||||
|
|
Loading…
Reference in New Issue