HAL_ChibiOS: fixed build for single FDCAN G4 boards

This commit is contained in:
Andrew Tridgell 2021-07-31 14:57:29 +10:00 committed by Peter Barker
parent 8df99f0d15
commit bab0c1dfc7

View File

@ -574,10 +574,12 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode)
nvicEnableVector(FDCAN1_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(FDCAN1_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(FDCAN1_IT1_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(FDCAN1_IT1_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
break; break;
#ifdef FDCAN2_IT0_IRQn
case 1: case 1:
nvicEnableVector(FDCAN2_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(FDCAN2_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(FDCAN2_IT1_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(FDCAN2_IT1_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
break; break;
#endif
#ifdef FDCAN3_IT0_IRQn #ifdef FDCAN3_IT0_IRQn
case 2: case 2:
nvicEnableVector(FDCAN3_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(FDCAN3_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY);