|
|
|
@ -31,6 +31,8 @@ extern const AP_HAL::HAL& hal;
@@ -31,6 +31,8 @@ extern const AP_HAL::HAL& hal;
|
|
|
|
|
extern AP_IOMCU iomcu; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#define RCOU_SERIAL_TIMING_DEBUG 0 |
|
|
|
|
|
|
|
|
|
struct RCOutput::pwm_group RCOutput::pwm_group_list[] = { HAL_PWM_GROUPS }; |
|
|
|
|
struct RCOutput::irq_state RCOutput::irq; |
|
|
|
|
|
|
|
|
@ -1035,6 +1037,10 @@ void RCOutput::serial_bit_irq(void)
@@ -1035,6 +1037,10 @@ void RCOutput::serial_bit_irq(void)
|
|
|
|
|
uint8_t bit = palReadLine(irq.line); |
|
|
|
|
bool send_signal = false; |
|
|
|
|
|
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG |
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO55, bit); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
if (irq.nbits == 0 || bit == irq.last_bit) { |
|
|
|
|
// start of byte, should be low
|
|
|
|
|
if (bit != 0) { |
|
|
|
@ -1125,6 +1131,11 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
@@ -1125,6 +1131,11 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
|
|
|
|
|
return false; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG |
|
|
|
|
hal.gpio->pinMode(54, 1); |
|
|
|
|
hal.gpio->pinMode(55, 1); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// assume GPIO mappings for PWM outputs start at 50
|
|
|
|
|
const uint8_t gpio_pin = 50 + chan; |
|
|
|
|
((GPIO *)hal.gpio)->_set_mode(gpio_pin, gpio_mode); |
|
|
|
@ -1139,7 +1150,14 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
@@ -1139,7 +1150,14 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
|
|
|
|
|
irq.last_bit = 0; |
|
|
|
|
irq.waiter = chThdGetSelfX(); |
|
|
|
|
|
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG |
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO54, 1); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
if (!hal.gpio->attach_interrupt(gpio_pin, serial_bit_irq, HAL_GPIO_INTERRUPT_BOTH)) { |
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG |
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO54, 0); |
|
|
|
|
#endif |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -1154,6 +1172,9 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
@@ -1154,6 +1172,9 @@ uint16_t RCOutput::serial_read_bytes(uint8_t *buf, uint16_t len)
|
|
|
|
|
|
|
|
|
|
((GPIO *)hal.gpio)->_set_mode(gpio_pin, restore_mode); |
|
|
|
|
chThdSetPriority(oldprio); |
|
|
|
|
#if RCOU_SERIAL_TIMING_DEBUG |
|
|
|
|
palWriteLine(HAL_GPIO_LINE_GPIO54, 0); |
|
|
|
|
#endif |
|
|
|
|
return i; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|