|
|
|
@ -648,7 +648,7 @@ void AP_Radio_cypress::radio_init(void)
@@ -648,7 +648,7 @@ void AP_Radio_cypress::radio_init(void)
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 |
|
|
|
|
stm32_gpiosetevent(CYRF_IRQ_INPUT, true, false, false, irq_radio_trampoline); |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS |
|
|
|
|
hal.gpio->attach_interrupt(HAL_GPIO_RADIO_IRQ, trigger_irq_radio_event, HAL_GPIO_INTERRUPT_RISING); |
|
|
|
|
hal.gpio->attach_interrupt(HAL_GPIO_RADIO_IRQ, trigger_irq_radio_event, AP_HAL::GPIO::INTERRUPT_RISING); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|