diff --git a/libraries/AP_HAL_ChibiOS/CanIface.cpp b/libraries/AP_HAL_ChibiOS/CanIface.cpp index 9d5feae1c8..15ed933ceb 100644 --- a/libraries/AP_HAL_ChibiOS/CanIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CanIface.cpp @@ -700,10 +700,6 @@ void CanIface::handleTxInterrupt(const uavcan::uint64_t utc_usec) update_event_.signalFromInterrupt(); pollErrorFlagsFromISR(); - - #if UAVCAN_STM32_FREERTOS - update_event_.yieldFromISR(); - #endif } void CanIface::handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t utc_usec) @@ -771,9 +767,6 @@ void CanIface::handleRxInterrupt(uavcan::uint8_t fifo_index, uavcan::uint64_t ut pollErrorFlagsFromISR(); - #if UAVCAN_STM32_FREERTOS - update_event_.yieldFromISR(); - #endif } void CanIface::pollErrorFlagsFromISR() @@ -937,25 +930,6 @@ uavcan::int16_t CanDriver::select(uavcan::CanSelectMasks& inout_masks, } -#if UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS - -static void nvicEnableVector(IRQn_Type irq, uint8_t prio) -{ - #if !defined (USE_HAL_DRIVER) - NVIC_InitTypeDef NVIC_InitStructure; - NVIC_InitStructure.NVIC_IRQChannel = irq; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = prio; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - #else - HAL_NVIC_SetPriority(irq, prio, 0); - HAL_NVIC_EnableIRQ(irq); - #endif -} - -#endif - void CanDriver::initOnce() { /*