mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_SITL: obey enable mask for output channels
This commit is contained in:
parent
9dc7dbfa16
commit
117974ef0f
@ -45,7 +45,7 @@ void RCOutput::disable_ch(uint8_t ch)
|
||||
|
||||
void RCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if (ch < SITL_NUM_CHANNELS) {
|
||||
if (ch < SITL_NUM_CHANNELS && (_enable_mask & (1U<<ch))) {
|
||||
if (_corked) {
|
||||
_pending[ch] = period_us;
|
||||
} else {
|
||||
|
Loading…
Reference in New Issue
Block a user