|
|
|
@ -1819,8 +1819,10 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
@@ -1819,8 +1819,10 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
|
|
|
|
|
} |
|
|
|
|
pwm_group &group = *serial_group; |
|
|
|
|
const ioline_t line = group.pal_lines[group.serial.chan]; |
|
|
|
|
uint32_t gpio_mode = PAL_MODE_INPUT_PULLUP; |
|
|
|
|
uint32_t restore_mode = PAL_MODE_ALTERNATE(group.alt_functions[group.serial.chan]) | PAL_STM32_OSPEED_MID2 | PAL_STM32_OTYPE_PUSHPULL; |
|
|
|
|
// keep speed low to avoid noise when switching between input and output
|
|
|
|
|
uint32_t gpio_mode = PAL_STM32_MODE_INPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_PUPDR_PULLUP | PAL_STM32_OSPEED_LOWEST; |
|
|
|
|
// restore the line to what it was before
|
|
|
|
|
iomode_t restore_mode = palReadLineMode(line); |
|
|
|
|
uint16_t i = 0; |
|
|
|
|
|
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG |
|
|
|
|