HAL_PX4: fixed enabled channels in init

now this is called from AP_BoardConfig we need to not clear enabled
channels
This commit is contained in:
Andrew Tridgell 2016-11-13 12:44:45 +11:00
parent 0502eca7fc
commit 00938f7dbb
1 changed files with 0 additions and 1 deletions

View File

@ -65,7 +65,6 @@ void PX4RCOutput::init()
#endif
// ensure not to write zeros to disabled channels
_enabled_channels = 0;
for (uint8_t i=0; i < PX4_NUM_OUTPUT_CHANNELS; i++) {
_period[i] = PWM_IGNORE_THIS_CHANNEL;
}