HAL_ChibiOS: fixed 2nd CAN inferface on F4/F7

CAN1_TX_IRQn is an enum not a defined. This was broken by the recent
change to support different CAN ordering
This commit is contained in:
Andrew Tridgell 2021-03-29 11:21:48 +11:00
parent e81dc36ed6
commit 07313ae71d

View File

@ -780,24 +780,26 @@ void CANIface::initOnce(bool enable_irq)
CriticalSectionLocker lock; CriticalSectionLocker lock;
switch (can_interfaces[self_index_]) { switch (can_interfaces[self_index_]) {
case 0: case 0:
#ifdef HAL_CAN_IFACE1_ENABLE
nvicEnableVector(CAN1_TX_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN1_TX_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(CAN1_RX0_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN1_RX0_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(CAN1_RX1_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN1_RX1_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
#endif
break; break;
#ifdef CAN2_TX_IRQn
case 1: case 1:
#ifdef HAL_CAN_IFACE2_ENABLE
nvicEnableVector(CAN2_TX_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN2_TX_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(CAN2_RX0_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN2_RX0_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(CAN2_RX1_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN2_RX1_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
break;
#endif #endif
#ifdef CAN3_TX_IRQn break;
case 2: case 2:
#ifdef HAL_CAN_IFACE3_ENABLE
nvicEnableVector(CAN3_TX_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN3_TX_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(CAN3_RX0_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN3_RX0_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(CAN3_RX1_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(CAN3_RX1_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
break;
#endif #endif
break;
} }
irq_init_ = true; irq_init_ = true;
} }