11 #if UAVCAN_STM32_CHIBIOS
13 #elif UAVCAN_STM32_NUTTX
14 # include <nuttx/arch.h>
15 # include <nuttx/irq.h>
16 # include <arch/board/board.h>
17 #elif UAVCAN_STM32_BAREMETAL
19 #elif UAVCAN_STM32_FREERTOS
24 #if (UAVCAN_STM32_CHIBIOS && CH_KERNEL_MAJOR == 2) || UAVCAN_STM32_BAREMETAL
25 # if !(defined(STM32F10X_CL) || defined(STM32F2XX) || defined(STM32F3XX) || defined(STM32F4XX))
27 # define CAN1_RX0_IRQn USB_LP_CAN1_RX0_IRQn
28 # define CAN1_TX_IRQn USB_HP_CAN1_TX_IRQn
30 # if !defined(CAN1_RX0_IRQHandler) || !defined(CAN1_TX_IRQHandler)
31 # define CAN1_TX_IRQHandler USB_HP_CAN1_TX_IRQHandler
32 # define CAN1_RX0_IRQHandler USB_LP_CAN1_RX0_IRQHandler
37 #if (UAVCAN_STM32_CHIBIOS && (CH_KERNEL_MAJOR == 3 || CH_KERNEL_MAJOR == 4 || CH_KERNEL_MAJOR == 5))
38 #define CAN1_TX_IRQHandler STM32_CAN1_TX_HANDLER
39 #define CAN1_RX0_IRQHandler STM32_CAN1_RX0_HANDLER
40 #define CAN1_RX1_IRQHandler STM32_CAN1_RX1_HANDLER
41 #define CAN2_TX_IRQHandler STM32_CAN2_TX_HANDLER
42 #define CAN2_RX0_IRQHandler STM32_CAN2_RX0_HANDLER
43 #define CAN2_RX1_IRQHandler STM32_CAN2_RX1_HANDLER
46 #if UAVCAN_STM32_NUTTX
47 # if !defined(STM32_IRQ_CAN1TX) && !defined(STM32_IRQ_CAN1RX0)
48 # define STM32_IRQ_CAN1TX STM32_IRQ_USBHPCANTX
49 # define STM32_IRQ_CAN1RX0 STM32_IRQ_USBLPCANRX0
53 static int can1_irq(
const int irq,
void*,
void*);
54 #if UAVCAN_STM32_NUM_IFACES > 1
55 static int can2_irq(
const int irq,
void*,
void*);
61 #if defined(STM32F3XX)
62 #define RCC_APB1ENR_CAN1EN RCC_APB1ENR_CANEN
63 #define RCC_APB1RSTR_CAN1RST RCC_APB1RSTR_CANRST
64 #define CAN1_TX_IRQn CAN_TX_IRQn
65 #define CAN1_RX0_IRQn CAN_RX0_IRQn
66 #define CAN1_RX1_IRQn CAN_RX1_IRQn
67 # if UAVCAN_STM32_BAREMETAL
68 # define CAN1_TX_IRQHandler CAN_TX_IRQHandler
69 # define CAN1_RX0_IRQHandler CAN_RX0_IRQHandler
70 # define CAN1_RX1_IRQHandler CAN_RX1_IRQHandler
80 CanIface* ifaces[UAVCAN_STM32_NUM_IFACES] =
83 #if UAVCAN_STM32_NUM_IFACES > 1
98 ifaces[iface_index]->handleTxInterrupt(
utc_usec);
116 ifaces[iface_index]->handleRxInterrupt(fifo_index,
utc_usec);
143 if (
in_ >= capacity_)
148 if (
len_ > capacity_)
153 if (
out_ >= capacity_)
168 if (
out_ >= capacity_)
197 if (target_bitrate < 1)
205 #if UAVCAN_STM32_BAREMETAL
207 #elif UAVCAN_STM32_CHIBIOS
209 #elif UAVCAN_STM32_NUTTX
211 #elif UAVCAN_STM32_FREERTOS
217 static const int MaxBS1 = 16;
218 static const int MaxBS2 = 8;
231 const int max_quanta_per_bit = (target_bitrate >= 1000000) ? 10 : 17;
235 static const int MaxSamplePointLocation = 900;
254 while ((prescaler_bs % (1 + bs1_bs2_sum)) != 0)
256 if (bs1_bs2_sum <= 2)
264 if ((prescaler < 1U) || (prescaler > 1024U))
296 sample_point_permill(0)
307 bool isValid()
const {
return (bs1 >= 1) && (bs1 <= MaxBS1) && (bs2 >= 1) && (bs2 <= MaxBS2); }
311 BsPair solution(bs1_bs2_sum,
uavcan::uint8_t(((7 * bs1_bs2_sum - 1) + 4) / 8));
313 if (solution.sample_point_permill > MaxSamplePointLocation)
316 solution = BsPair(bs1_bs2_sum,
uavcan::uint8_t((7 * bs1_bs2_sum - 1) / 8));
328 if ((target_bitrate != (pclk / (prescaler * (1 + solution.bs1 + solution.bs2)))) || !solution.isValid())
335 int(1 + solution.bs1 + solution.bs2),
float(solution.sample_point_permill) / 10.F);
367 CriticalSectionLocker lock;
441 CriticalSectionLocker lock;
457 CriticalSectionLocker lock;
471 if (num_configs == 0)
476 can_->
FA1R |= 1U << filter_start_index;
519 can_->
FA1R |= (1 << (filter_start_index + i));
523 can_->
FA1R &= ~(1 << (filter_start_index + i));
538 #if UAVCAN_STM32_NUTTX || UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_FREERTOS
539 const unsigned Timeout = 1000;
541 const unsigned Timeout = 2000000;
543 for (
unsigned wait_ack = 0; wait_ack < Timeout; wait_ack++)
546 if (state == target_state)
550 #if UAVCAN_STM32_NUTTX
553 #if UAVCAN_STM32_CHIBIOS
555 ::chThdSleep(MS2ST(1));
557 ::chThdSleep(TIME_MS2I(1));
560 #if UAVCAN_STM32_FREERTOS
573 CriticalSectionLocker lock;
609 unsigned(timings.
prescaler),
unsigned(timings.
sjw),
unsigned(timings.
bs1),
unsigned(timings.
bs2));
617 ((timings.
bs1 & 15U) << 16) |
618 ((timings.
bs2 & 7U) << 20) |
648 #if UAVCAN_STM32_NUM_IFACES > 1
709 #if UAVCAN_STM32_FREERTOS
776 #if UAVCAN_STM32_FREERTOS
805 CriticalSectionLocker lock;
843 CriticalSectionLocker lock;
858 CriticalSectionLocker lock;
864 CriticalSectionLocker lock;
870 CriticalSectionLocker lock;
876 CriticalSectionLocker lock;
890 msk.
read = if0_.isRxBufferEmpty() ? 0 : 1;
894 msk.
write = if0_.canAcceptNewTxFrame(*pending_tx[0]) ? 1 : 0;
898 #if UAVCAN_STM32_NUM_IFACES > 1
899 if (!if1_.isRxBufferEmpty())
906 if (if1_.canAcceptNewTxFrame(*pending_tx[1]))
917 #if UAVCAN_STM32_NUM_IFACES == 1
918 return !if0_.isRxBufferEmpty();
919 #elif UAVCAN_STM32_NUM_IFACES == 2
920 return !if0_.isRxBufferEmpty() || !if1_.isRxBufferEmpty();
922 # error UAVCAN_STM32_NUM_IFACES
933 if0_.discardTimedOutTxMailboxes(time);
935 CriticalSectionLocker cs_locker;
936 if0_.pollErrorFlagsFromISR();
939 #if UAVCAN_STM32_NUM_IFACES > 1
940 if1_.discardTimedOutTxMailboxes(time);
942 CriticalSectionLocker cs_locker;
943 if1_.pollErrorFlagsFromISR();
947 inout_masks = makeSelectMasks(pending_tx);
948 if ((inout_masks.
read & in_masks.
read) != 0 ||
955 inout_masks = makeSelectMasks(pending_tx);
960 #if UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
962 static void nvicEnableVector(IRQn_Type irq,
uint8_t prio)
964 #if !defined (USE_HAL_DRIVER)
965 NVIC_InitTypeDef NVIC_InitStructure;
966 NVIC_InitStructure.NVIC_IRQChannel = irq;
967 NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = prio;
968 NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
969 NVIC_InitStructure.NVIC_IRQChannelCmd =
ENABLE;
970 NVIC_Init(&NVIC_InitStructure);
972 HAL_NVIC_SetPriority(irq, prio, 0);
973 HAL_NVIC_EnableIRQ(irq);
985 CriticalSectionLocker lock;
986 #if defined(STM32L4xx)
987 #if UAVCAN_STM32_NUTTX
988 modifyreg32(STM32_RCC_APB1ENR1, 0, RCC_APB1ENR1_CAN1EN);
989 modifyreg32(STM32_RCC_APB1RSTR1, 0, RCC_APB1RSTR1_CAN1RST);
990 modifyreg32(STM32_RCC_APB1RSTR1, RCC_APB1RSTR1_CAN1RST, 0);
991 # if UAVCAN_STM32_NUM_IFACES > 1
992 modifyreg32(STM32_RCC_APB1ENR1, 0, RCC_APB1ENR1_CAN2EN);
993 modifyreg32(STM32_RCC_APB1RSTR1, 0, RCC_APB1RSTR1_CAN2RST);
994 modifyreg32(STM32_RCC_APB1RSTR1, RCC_APB1RSTR1_CAN2RST, 0);
997 RCC->APB1ENR1 |= RCC_APB1ENR1_CAN1EN;
998 RCC->APB1RSTR1 |= RCC_APB1RSTR1_CAN1RST;
999 RCC->APB1RSTR1 &= ~RCC_APB1RSTR1_CAN1RST;
1000 # if UAVCAN_STM32_NUM_IFACES > 1
1001 RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
1002 RCC->APB1RSTR |= RCC_APB1RSTR_CAN2RST;
1003 RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN2RST;
1007 # if UAVCAN_STM32_NUTTX
1008 modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN1EN);
1009 modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_CAN1RST);
1010 modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_CAN1RST, 0);
1011 # if UAVCAN_STM32_NUM_IFACES > 1
1012 modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_CAN2EN);
1013 modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_CAN2RST);
1014 modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_CAN2RST, 0);
1017 RCC->APB1ENR |= RCC_APB1ENR_CAN1EN;
1018 RCC->APB1RSTR |= RCC_APB1RSTR_CAN1RST;
1019 RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN1RST;
1020 # if UAVCAN_STM32_NUM_IFACES > 1
1021 RCC->APB1ENR |= RCC_APB1ENR_CAN2EN;
1022 RCC->APB1RSTR |= RCC_APB1RSTR_CAN2RST;
1023 RCC->APB1RSTR &= ~RCC_APB1RSTR_CAN2RST;
1032 #if UAVCAN_STM32_NUTTX
1033 # define IRQ_ATTACH(irq, handler) \
1035 const int res = irq_attach(irq, handler, NULL); \
1038 up_enable_irq(irq); \
1043 # if UAVCAN_STM32_NUM_IFACES > 1
1049 #elif UAVCAN_STM32_CHIBIOS || UAVCAN_STM32_BAREMETAL || UAVCAN_STM32_FREERTOS
1051 CriticalSectionLocker lock;
1052 nvicEnableVector(CAN1_TX_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1053 nvicEnableVector(CAN1_RX0_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1054 nvicEnableVector(CAN1_RX1_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1055 # if UAVCAN_STM32_NUM_IFACES > 1
1056 nvicEnableVector(CAN2_TX_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1057 nvicEnableVector(CAN2_RX0_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1058 nvicEnableVector(CAN2_RX1_IRQn, UAVCAN_STM32_IRQ_PRIORITY_MASK);
1068 UAVCAN_STM32_LOG(
"Bitrate %lu mode %d",
static_cast<unsigned long>(bitrate),
static_cast<int>(mode));
1070 static bool initialized_once =
false;
1071 if (!initialized_once)
1073 initialized_once =
true;
1083 res = if0_.init(bitrate, mode);
1094 #if UAVCAN_STM32_NUM_IFACES > 1
1097 res = if1_.init(bitrate, mode);
1118 if (iface_index < UAVCAN_STM32_NUM_IFACES)
1120 return ifaces[iface_index];
1127 bool ret = if0_.hadActivity();
1128 #if UAVCAN_STM32_NUM_IFACES > 1
1129 ret |= if1_.hadActivity();
1142 #if UAVCAN_STM32_NUTTX
1144 static int can1_irq(
const int irq,
void*,
void*)
1146 if (irq == STM32_IRQ_CAN1TX)
1148 uavcan_stm32::handleTxInterrupt(0);
1150 else if (irq == STM32_IRQ_CAN1RX0)
1152 uavcan_stm32::handleRxInterrupt(0, 0);
1154 else if (irq == STM32_IRQ_CAN1RX1)
1156 uavcan_stm32::handleRxInterrupt(0, 1);
1165 # if UAVCAN_STM32_NUM_IFACES > 1
1167 static int can2_irq(
const int irq,
void*,
void*)
1169 if (irq == STM32_IRQ_CAN2TX)
1171 uavcan_stm32::handleTxInterrupt(1);
1173 else if (irq == STM32_IRQ_CAN2RX0)
1175 uavcan_stm32::handleRxInterrupt(1, 0);
1177 else if (irq == STM32_IRQ_CAN2RX1)
1179 uavcan_stm32::handleRxInterrupt(1, 1);
1190 #else // UAVCAN_STM32_NUTTX
1192 #if !defined(CAN1_TX_IRQHandler) ||\
1193 !defined(CAN1_RX0_IRQHandler) ||\
1194 !defined(CAN1_RX1_IRQHandler)
1195 # error "Misconfigured build"
1202 uavcan_stm32::handleTxInterrupt(0);
1210 uavcan_stm32::handleRxInterrupt(0, 0);
1218 uavcan_stm32::handleRxInterrupt(0, 1);
1222 # if UAVCAN_STM32_NUM_IFACES > 1
1224 #if !defined(CAN2_TX_IRQHandler) ||\
1225 !defined(CAN2_RX0_IRQHandler) ||\
1226 !defined(CAN2_RX1_IRQHandler)
1227 # error "Misconfigured build"
1234 uavcan_stm32::handleTxInterrupt(1);
1242 uavcan_stm32::handleRxInterrupt(1, 0);
1250 uavcan_stm32::handleRxInterrupt(1, 1);
1255 #endif // UAVCAN_STM32_NUTTX