Browse Source

AP_IOMCU: disable DSM and SBUS for pulse input

master
Andrew Tridgell 6 years ago
parent
commit
e6cadfa2d9
  1. 2
      libraries/AP_IOMCU/iofirmware/iofirmware.cpp
  2. 9
      libraries/AP_IOMCU/iofirmware/rc.cpp

2
libraries/AP_IOMCU/iofirmware/iofirmware.cpp

@ -171,8 +171,6 @@ void AP_IOMCU_FW::init() @@ -171,8 +171,6 @@ void AP_IOMCU_FW::init()
palSetLineMode(HAL_GPIO_PIN_SPEKTRUM_PWR_EN, PAL_MODE_OUTPUT_PUSHPULL);
SPEKTRUM_POWER(1);
rcprotocol = AP_RCProtocol::get_instance();
// we do no allocations after setup completes
reg_status.freemem = hal.util->available_memory();
}

9
libraries/AP_IOMCU/iofirmware/rc.cpp

@ -66,6 +66,15 @@ void AP_IOMCU_FW::rcin_serial_init(void) @@ -66,6 +66,15 @@ void AP_IOMCU_FW::rcin_serial_init(void)
&sd3_listener,
EVENT_MASK(1),
SD_PARITY_ERROR);
rcprotocol = AP_RCProtocol::get_instance();
// disable input for DSM and SBUS with pulses, we will use uarts
// for those. This allows us to use the RCIN port for a much wider
// range of protocols, relying on the 16 bit CRC on those
// protocols to keep them glitch free
rcprotocol->disable_for_pulses(AP_RCProtocol::SBUS);
rcprotocol->disable_for_pulses(AP_RCProtocol::SBUS_NI);
rcprotocol->disable_for_pulses(AP_RCProtocol::DSM);
}
static struct {

Loading…
Cancel
Save