mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Fix bug where STM32L496 would not init CAN2
This is due to the way that the APB peripheral was configured. RCC_APB1ENR1_CAN2EN was not accounted for in the CAN hardware init, so CAN2 clock init was never attempted. I copied the way CAN1 is initialized based on different hardware description headers.
This commit is contained in:
parent
bfbc76e172
commit
805ed73d94
|
@ -774,7 +774,13 @@ void CANIface::initOnce(bool enable_irq)
|
|||
RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN1RST;
|
||||
#endif
|
||||
break;
|
||||
#ifdef RCC_APB1ENR_CAN2EN
|
||||
#if defined(RCC_APB1ENR1_CAN2EN)
|
||||
case 1:
|
||||
RCC->APB1ENR1 |= RCC_APB1ENR1_CAN2EN;
|
||||
RCC->APB1RSTR1 |= RCC_APB1RSTR1_CAN2RST;
|
||||
RCC->APB1RSTR1 &= ~RCC_APB1RSTR1_CAN2RST;
|
||||
break;
|
||||
#elif defined(RCC_APB1ENR_CAN2EN)
|
||||
case 1:
|
||||
RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
|
||||
RCC->APB1RSTR |= RCC_APB1RSTR_CAN2RST;
|
||||
|
|
Loading…
Reference in New Issue