Browse Source

AP_HAL_ChibiOS: fix invalid use of FDCAN2_IT0_IRQn enum for ifdef

gps-1.3.1
bugobliterator 4 years ago committed by Andrew Tridgell
parent
commit
81c5a99527
  1. 4
      libraries/AP_HAL_ChibiOS/CANFDIface.cpp

4
libraries/AP_HAL_ChibiOS/CANFDIface.cpp

@ -574,13 +574,13 @@ 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 #ifdef FDCAN2
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 #endif
#ifdef FDCAN3_IT0_IRQn #ifdef FDCAN3
case 2: case 2:
nvicEnableVector(FDCAN3_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(FDCAN3_IT0_IRQn, CORTEX_MAX_KERNEL_PRIORITY);
nvicEnableVector(FDCAN3_IT1_IRQn, CORTEX_MAX_KERNEL_PRIORITY); nvicEnableVector(FDCAN3_IT1_IRQn, CORTEX_MAX_KERNEL_PRIORITY);

Loading…
Cancel
Save