diff --git a/arch/arm/src/imxrt/Kconfig b/arch/arm/src/imxrt/Kconfig index 0364e476dba59..8cb93b45945cc 100644 --- a/arch/arm/src/imxrt/Kconfig +++ b/arch/arm/src/imxrt/Kconfig @@ -155,6 +155,11 @@ config IMXRT_HAVE_LPUART bool default n +config IMXRT_FLEXCAN + bool + default n + select ARCH_HAVE_NETDEV_STATISTICS + config IMXRT_LPI2C bool default n @@ -411,6 +416,94 @@ config IMXRT_LPUART_INVERT endmenu # LPUART Configuration +menu "FLEXCAN Peripherals" + +config IMXRT_FLEXCAN1 + bool "FLEXCAN1" + default n + select IMXRT_FLEXCAN + select NET_CAN_HAVE_TX_DEADLINE + +config IMXRT_FLEXCAN2 + bool "FLEXCAN2" + default n + select IMXRT_FLEXCAN + select NET_CAN_HAVE_TX_DEADLINE + +config IMXRT_FLEXCAN3 + bool "FLEXCAN3" + default n + select IMXRT_FLEXCAN + select NET_CAN_HAVE_TX_DEADLINE + select NET_CAN_HAVE_CANFD + +endmenu # FLEXCAN Peripherals + +menu "FLEXCAN1 Configuration" + depends on IMXRT_FLEXCAN1 + +config FLEXCAN1_BITRATE + int "CAN bitrate" + depends on !NET_CAN_CANFD + default 1000000 + +config FLEXCAN1_SAMPLEP + int "CAN sample point" + depends on !NET_CAN_CANFD + default 80 + +endmenu # IMXRT_FLEXCAN1 + +menu "FLEXCAN2 Configuration" + depends on IMXRT_FLEXCAN2 + +config FLEXCAN2_BITRATE + int "CAN bitrate" + depends on !NET_CAN_CANFD + default 1000000 + +config FLEXCAN2_SAMPLEP + int "CAN sample point" + depends on !NET_CAN_CANFD + default 80 + +endmenu # IMXRT_FLEXCAN2 + +menu "FLEXCAN3 Configuration" + depends on IMXRT_FLEXCAN3 + +config FLEXCAN3_BITRATE + int "CAN bitrate" + depends on !NET_CAN_CANFD + default 1000000 + +config FLEXCAN3_SAMPLEP + int "CAN sample point" + depends on !NET_CAN_CANFD + default 80 + +config FLEXCAN3_ARBI_BITRATE + int "CAN FD Arbitration phase bitrate" + depends on NET_CAN_CANFD + default 1000000 + +config FLEXCAN3_ARBI_SAMPLEP + int "CAN FD Arbitration phase sample point" + depends on NET_CAN_CANFD + default 80 + +config FLEXCAN3_DATA_BITRATE + int "CAN FD Data phase bitrate" + depends on NET_CAN_CANFD + default 4000000 + +config FLEXCAN3_DATA_SAMPLEP + int "CAN FD Data phase sample point" + depends on NET_CAN_CANFD + default 90 + +endmenu # IMXRT_FLEXCAN3 + menu "LPI2C Peripherals" menuconfig IMXRT_LPI2C1 diff --git a/arch/arm/src/imxrt/Make.defs b/arch/arm/src/imxrt/Make.defs index bfcefe5202e9a..b6f9d1b336296 100644 --- a/arch/arm/src/imxrt/Make.defs +++ b/arch/arm/src/imxrt/Make.defs @@ -133,6 +133,10 @@ ifeq ($(CONFIG_IMXRT_LCD),y) CHIP_CSRCS += imxrt_lcd.c endif +ifeq ($(CONFIG_IMXRT_FLEXCAN),y) +CHIP_CSRCS += imxrt_flexcan.c +endif + ifeq ($(CONFIG_IMXRT_SNVS_LPSRTC),y) CHIP_CSRCS += imxrt_lpsrtc.c CHIP_CSRCS += imxrt_hprtc.c diff --git a/arch/arm/src/imxrt/hardware/imxrt_flexcan.h b/arch/arm/src/imxrt/hardware/imxrt_flexcan.h new file mode 100644 index 0000000000000..f02a31f9b0028 --- /dev/null +++ b/arch/arm/src/imxrt/hardware/imxrt_flexcan.h @@ -0,0 +1,463 @@ +/**************************************************************************** + * arch/arm/src/imxrt/hardware/imxrt_flexcan.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_IMXRT_HARDWARE_IMXRT_FLEXCAN_H +#define __ARCH_ARM_SRC_IMXRT_HARDWARE_IMXRT_FLEXCAN_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "chip.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Register Offsets *********************************************************/ + +#define IMXRT_CAN_MCR_OFFSET 0x0000 /* Module Configuration Register */ +#define IMXRT_CAN_CTRL1_OFFSET 0x0004 /* Control 1 Register */ +#define IMXRT_CAN_TIMER_OFFSET 0x0008 /* Free Running Timer */ +#define IMXRT_CAN_RXMGMASK_OFFSET 0x0010 /* Rx Mailboxes Global Mask Register */ +#define IMXRT_CAN_RX14MASK_OFFSET 0x0014 /* Rx 14 Mask Register */ +#define IMXRT_CAN_RX15MASK_OFFSET 0x0018 /* Rx 15 Mask Register */ +#define IMXRT_CAN_ECR_OFFSET 0x001c /* Error Counter */ +#define IMXRT_CAN_ESR1_OFFSET 0x0020 /* Error and Status 1 Register */ +#define IMXRT_CAN_IMASK2_OFFSET 0x0024 /* Interrupt Masks 2 Register */ +#define IMXRT_CAN_IMASK1_OFFSET 0x0028 /* Interrupt Masks 1 Register */ +#define IMXRT_CAN_IFLAG2_OFFSET 0x002c /* Interrupt Flags 2 Register */ +#define IMXRT_CAN_IFLAG1_OFFSET 0x0030 /* Interrupt Flags 1 Register */ +#define IMXRT_CAN_CTRL2_OFFSET 0x0034 /* Control 2 Register */ +#define IMXRT_CAN_ESR2_OFFSET 0x0038 /* Error and Status 2 Register */ +#define IMXRT_CAN_CRCR_OFFSET 0x0044 /* CRC Register */ +#define IMXRT_CAN_RXFGMASK_OFFSET 0x0048 /* Rx FIFO Global Mask Register */ +#define IMXRT_CAN_RXFIR_OFFSET 0x004c /* Rx FIFO Information Register */ +#define IMXRT_CAN_CBT_OFFSET 0x0050 /* CAN Bit Timing Register */ + +#define IMXRT_CAN_MB_OFFSET 0x0080 /* CAN MB register */ + +#define IMXRT_CAN_RXIMR_OFFSET(n) (0x0880+((n)<<2)) /* Rn Individual Mask Registers */ +#define IMXRT_CAN_RXIMR0_OFFSET 0x0880 /* R0 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR1_OFFSET 0x0884 /* R1 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR2_OFFSET 0x0888 /* R2 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR3_OFFSET 0x088c /* R3 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR4_OFFSET 0x0890 /* R4 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR5_OFFSET 0x0894 /* R5 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR6_OFFSET 0x0898 /* R6 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR7_OFFSET 0x089c /* R7 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR8_OFFSET 0x08a0 /* R8 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR9_OFFSET 0x08a4 /* R9 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR10_OFFSET 0x08a8 /* R10 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR11_OFFSET 0x08ac /* R11 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR12_OFFSET 0x08b0 /* R12 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR13_OFFSET 0x08b4 /* R13 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR14_OFFSET 0x08b8 /* R14 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR15_OFFSET 0x08bc /* R15 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR16_OFFSET 0x08c0 /* R16 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR17_OFFSET 0x08c4 /* R17 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR18_OFFSET 0x08c8 /* R18 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR19_OFFSET 0x08cc /* R19 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR20_OFFSET 0x08d0 /* R20 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR21_OFFSET 0x08d4 /* R21 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR22_OFFSET 0x08d8 /* R22 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR23_OFFSET 0x08dc /* R23 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR24_OFFSET 0x08e0 /* R24 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR25_OFFSET 0x08e4 /* R25 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR26_OFFSET 0x08e8 /* R26 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR27_OFFSET 0x08ec /* R27 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR28_OFFSET 0x08f0 /* R28 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR29_OFFSET 0x08f4 /* R29 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR30_OFFSET 0x08f8 /* R30 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR31_OFFSET 0x08fc /* R31 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR32_OFFSET 0x0900 /* R32 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR33_OFFSET 0x0904 /* R33 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR34_OFFSET 0x0908 /* R34 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR35_OFFSET 0x090c /* R35 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR36_OFFSET 0x0910 /* R36 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR37_OFFSET 0x0914 /* R37 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR38_OFFSET 0x0918 /* R38 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR39_OFFSET 0x091c /* R39 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR40_OFFSET 0x0920 /* R40 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR41_OFFSET 0x0924 /* R41 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR42_OFFSET 0x0928 /* R42 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR43_OFFSET 0x092c /* R43 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR44_OFFSET 0x0930 /* R44 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR45_OFFSET 0x0934 /* R45 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR46_OFFSET 0x0938 /* R46 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR47_OFFSET 0x093c /* R47 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR48_OFFSET 0x0940 /* R48 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR49_OFFSET 0x0944 /* R49 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR50_OFFSET 0x0948 /* R50 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR51_OFFSET 0x094c /* R51 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR52_OFFSET 0x0950 /* R52 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR53_OFFSET 0x0954 /* R53 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR54_OFFSET 0x0958 /* R54 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR55_OFFSET 0x095c /* R55 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR56_OFFSET 0x0960 /* R56 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR57_OFFSET 0x0964 /* R57 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR58_OFFSET 0x0968 /* R58 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR59_OFFSET 0x096c /* R59 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR60_OFFSET 0x0970 /* R60 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR61_OFFSET 0x0974 /* R61 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR62_OFFSET 0x0978 /* R62 Individual Mask Registers */ +#define IMXRT_CAN_RXIMR63_OFFSET 0x097c /* R63 Individual Mask Registers */ + +#ifdef CONFIG_IMXRT_FLEXCAN3 +#define IMXRT_CAN_FDCTRL_OFFSET 0x0c00 /* CAN FD Control Register */ +#define IMXRT_CAN_FDCBT_OFFSET 0x0c04 /* CAN FD Bit Timing Register */ +#define IMXRT_CAN_FDCRC_OFFSET 0x0c08 /* CAN FD CRC register */ +#endif /* CONFIG_IMXRT_FLEXCAN3 */ + +/* Register Bit Definitions *************************************************/ + +/* Module Configuration Register */ + +#define CAN_MCR_MAXMB_SHIFT (0) /* Bits 0-6: Number of the Last Message Buffer */ +#define CAN_MCR_MAXMB_MASK (0x7f << CAN_MCR_MAXMB_SHIFT) + /* Bit 7: Reserved */ +#define CAN_MCR_IDAM_SHIFT (8) /* Bits 8-9: ID Acceptance Mode */ +#define CAN_MCR_IDAM_MASK (3 << CAN_MCR_IDAM_SHIFT) +# define CAN_MCR_IDAM_FMTA (0 << CAN_MCR_IDAM_SHIFT) /* Format A: One full ID */ +# define CAN_MCR_IDAM_FMTB (1 << CAN_MCR_IDAM_SHIFT) /* Format B: Two full (or partial) IDs */ +# define CAN_MCR_IDAM_FMTC (2 << CAN_MCR_IDAM_SHIFT) /* Format C: Four partial IDs */ +# define CAN_MCR_IDAM_FMTD (3 << CAN_MCR_IDAM_SHIFT) /* Format D: All frames rejected */ + + /* Bit 10: Reserved */ +#ifdef CONFIG_IMXRT_FLEXCAN3 +# define CAN_MCR_FDEN (1 << 11) /* Bit 11: CAN FD Operation Enable */ +#endif /* Bit 11: Reserved for FlexCAN1 and FlexCAN2 */ +#define CAN_MCR_AEN (1 << 12) /* Bit 12: Abort Enable */ +#define CAN_MCR_LPRIOEN (1 << 13) /* Bit 13: Local Priority Enable */ + /* Bit 14: Reserved */ +#ifdef CONFIG_IMXRT_FLEXCAN3 +# define CAN_MCR_DMA (1 << 15) /* Bit 15: DMA Enable */ +#endif /* Bit 15: Reserved for FlexCAN1 and FlexCAN2 */ +#define CAN_MCR_IRMQ (1 << 16) /* Bit 16: Individual Rx Masking and Queue Enable */ +#define CAN_MCR_SRXDIS (1 << 17) /* Bit 17: Self Reception Disable */ +#ifdef CONFIG_IMXRT_FLEXCAN3 +# define CAN_MCR_DOZE (1 << 18) /* Bit 18: Doze Mode Enable */ +#endif /* Bit 18: Reserved for FlexCAN1 and FlexCAN2 */ +#define CAN_MCR_WAKSRC (1 << 19) /* Bit 19: Wake Up Source */ +#define CAN_MCR_LPMACK (1 << 20) /* Bit 20: Low Power Mode Acknowledge */ +#define CAN_MCR_WRNEN (1 << 21) /* Bit 21: Warning Interrupt Enable */ +#define CAN_MCR_SLFWAK (1 << 22) /* Bit 22: Self Wake Up */ +#define CAN_MCR_SUPV (1 << 23) /* Bit 23: Supervisor Mode */ +#define CAN_MCR_FRZACK (1 << 24) /* Bit 24: Freeze Mode Acknowledge */ +#define CAN_MCR_SOFTRST (1 << 25) /* Bit 25: Soft Reset */ +#define CAN_MCR_WAKMSK (1 << 26) /* Bit 26: Wake Up Interrupt Mask */ +#define CAN_MCR_NOTRDY (1 << 27) /* Bit 27: FlexCAN Not Ready */ +#define CAN_MCR_HALT (1 << 28) /* Bit 28: Halt FlexCAN */ +#define CAN_MCR_RFEN (1 << 29) /* Bit 29: Rx FIFO Enable */ +#define CAN_MCR_FRZ (1 << 30) /* Bit 30: Freeze Enable */ +#define CAN_MCR_MDIS (1 << 31) /* Bit 31: Module Disable */ + +/* Control 1 Register */ + +#define CAN_CTRL1_PROPSEG_SHIFT (0) /* Bits 0-2: Propagation Segment */ +#define CAN_CTRL1_PROPSEG_MASK (7 << CAN_CTRL1_PROPSEG_SHIFT) +#define CAN_CTRL1_PROPSEG(x) (((uint32_t)(((uint32_t)(x)) << CAN_CTRL1_PROPSEG_SHIFT)) & CAN_CTRL1_PROPSEG_MASK) +#define CAN_CTRL1_LOM (1 << 3) /* Bit 3: Listen-Only Mode */ +#define CAN_CTRL1_LBUF (1 << 4) /* Bit 4: Lowest Buffer Transmitted First */ +#define CAN_CTRL1_TSYN (1 << 5) /* Bit 5: Timer Sync */ +#define CAN_CTRL1_BOFFREC (1 << 6) /* Bit 6: Bus Off Recovery */ +#define CAN_CTRL1_SMP (1 << 7) /* Bit 7: CAN Bit Sampling */ + /* Bits 8-9: Reserved */ +#define CAN_CTRL1_RWRNMSK (1 << 10) /* Bit 10: Rx Warning Interrupt Mask */ +#define CAN_CTRL1_TWRNMSK (1 << 11) /* Bit 11: Tx Warning Interrupt Mask */ +#define CAN_CTRL1_LPB (1 << 12) /* Bit 12: Loop Back Mode */ +#ifdef CONFIG_IMXRT_FLEXCAN3 +# define CAN_CTRL1_CLKSRC (1 << 13) /* Bit 13: CAN Engine Clock Source */ +#endif /* Bit 13: Reserved for FlexCAN1 and FlexCAN2 */ +#define CAN_CTRL1_ERRMSK (1 << 14) /* Bit 14: Error Mask */ +#define CAN_CTRL1_BOFFMSK (1 << 15) /* Bit 15: Bus Off Mask */ +#define CAN_CTRL1_PSEG2_SHIFT (16) /* Bits 16-18: Phase Segment 2 */ +#define CAN_CTRL1_PSEG2_MASK (7 << CAN_CTRL1_PSEG2_SHIFT) +#define CAN_CTRL1_PSEG2(x) (((uint32_t)(((uint32_t)(x)) << CAN_CTRL1_PSEG2_SHIFT)) & CAN_CTRL1_PSEG2_MASK) +#define CAN_CTRL1_PSEG1_SHIFT (19) /* Bits 19-21: Phase Segment 1 */ +#define CAN_CTRL1_PSEG1_MASK (7 << CAN_CTRL1_PSEG1_SHIFT) +#define CAN_CTRL1_PSEG1(x) (((uint32_t)(((uint32_t)(x)) << CAN_CTRL1_PSEG1_SHIFT)) & CAN_CTRL1_PSEG1_MASK) +#define CAN_CTRL1_RJW_SHIFT (22) /* Bits 22-23: Resync Jump Width */ +#define CAN_CTRL1_RJW_MASK (3 << CAN_CTRL1_RJW_SHIFT) +#define CAN_CTRL1_RJW(x) (((uint32_t)(((uint32_t)(x)) << CAN_CTRL1_RJW_SHIFT)) & CAN_CTRL1_RJW_MASK) +#define CAN_CTRL1_PRESDIV_SHIFT (24) /* Bits 24-31: Prescaler Division Factor */ +#define CAN_CTRL1_PRESDIV_MASK (0xff << CAN_CTRL1_PRESDIV_SHIFT) +#define CAN_CTRL1_PRESDIV(x) (((uint32_t)(((uint32_t)(x)) << CAN_CTRL1_PRESDIV_SHIFT)) & CAN_CTRL1_PRESDIV_MASK) + +/* Free Running Timer */ + +#define CAN_TIMER_SHIFT (0) /* Bits 0-15: Timer value */ +#define CAN_TIMER_MASK (0xffff << CAN_TIMER_SHIFT) + /* Bits 16-31: Reserved */ + +/* Rx Mailboxes Global Mask Register (32 Rx Mailboxes Global Mask Bits) */ + +#define CAN_RXMGMASK(n) (1 << (n)) /* Bit n: Rx Mailboxe n Global Mask Bit */ + +/* Rx 14 Mask Register */ + +#define CAN_RX14MASK(n) (1 << (n)) /* Bit n: Rx Buffer 14 Mask Bit n */ + +/* Rx 15 Mask Register */ + +#define CAN_RX15MASK(n) (1 << (n)) /* Bit n: Rx Buffer 15 Mask Bit n */ + +/* Error Counter */ + +#define CAN_ECR_TXERRCNT_SHIFT (0) /* Bits 0-7: Transmit Error Counter */ +#define CAN_ECR_TXERRCNT_MASK (0xff << CAN_ECR_TXERRCNT_SHIFT) +#define CAN_ECR_RXERRCNT_SHIFT (8) /* Bits 8-15: Receive Error Counter */ +#define CAN_ECR_RXERRCNT_MASK (0xff << CAN_ECR_RXERRCNT_SHIFT) +#ifdef CONFIG_IMXRT_FLEXCAN3 +# define CAN_ECR_TXERRCNTFAST_SHIFT (16) /* Bits 16-23: Transmit Error Counter for fast bits */ +# define CAN_ECR_TXERRCNTFAST_MASK (0xff << CAN_ECR_TXERRCNTFAST_SHIFT) +# define CAN_ECR_RXERRCNTFAST_SHIFT (24) /* Bits 24-31: Receive Error Counter for fast bits */ +# define CAN_ECR_RXERRCNTFAST_MASK (0xff << CAN_ECR_RXERRCNTFAST_SHIFT) +#endif /* Bits 16-31: Reserved for FlexCAN1 and FlexCAN2 */ + +/* Error and Status 1 Register */ + +#define CAN_ESR1_WAKINT (1 << 0) /* Bit 0: Wake-Up Interrupt */ +#define CAN_ESR1_ERRINT (1 << 1) /* Bit 1: Error Interrupt */ +#define CAN_ESR1_BOFFINT (1 << 2) /* Bit 2: 'Bus Off' Interrupt */ +#define CAN_ESR1_RX (1 << 3) /* Bit 3: FlexCAN in Reception */ +#define CAN_ESR1_FLTCONF_SHIFT (4) /* Bits 4-5: Fault Confinement State */ +#define CAN_ESR1_FLTCONF_MASK (3 << CAN_ESR1_FLTCONF_SHIFT) +# define CAN_ESR1_FLTCONF_ACTV (0 << CAN_ESR1_FLTCONF_SHIFT) + /* Error Active */ +# define CAN_ESR1_FLTCONF_PASV (1 << CAN_ESR1_FLTCONF_SHIFT) + /* Error Passive */ +# define CAN_ESR1_FLTCONF_OFF (2 << CAN_ESR1_FLTCONF_SHIFT) + /* Bus Off */ +#define CAN_ESR1_TX (1 << 6) /* Bit 6: FlexCAN in Transmission */ +#define CAN_ESR1_IDLE (1 << 7) /* Bit 7: CAN bus is in IDLE state */ +#define CAN_ESR1_RXWRN (1 << 8) /* Bit 8: Rx Error Warning */ +#define CAN_ESR1_TXWRN (1 << 9) /* Bit 9: TX Error Warning */ +#define CAN_ESR1_STFERR (1 << 10) /* Bit 10: Stuffing Error */ +#define CAN_ESR1_FRMERR (1 << 11) /* Bit 11: Form Error */ +#define CAN_ESR1_CRCERR (1 << 12) /* Bit 12: Cyclic Redundancy Check Error */ +#define CAN_ESR1_ACKERR (1 << 13) /* Bit 13: Acknowledge Error */ +#define CAN_ESR1_BIT0ERR (1 << 14) /* Bit 14: Bit0 Error */ +#define CAN_ESR1_BIT1ERR (1 << 15) /* Bit 15: Bit1 Error */ +#define CAN_ESR1_RWRNINT (1 << 16) /* Bit 16: Rx Warning Interrupt Flag */ +#define CAN_ESR1_TWRNINT (1 << 17) /* Bit 17: Tx Warning Interrupt Flag */ +#define CAN_ESR1_SYNCH (1 << 18) /* Bit 18: CAN Synchronization Status */ +#ifdef CONFIG_IMXRT_FLEXCAN3 +#define CAN_ESR1_BOFFDONEINT (1 << 19) /* Bit 19: Bus Off Done Interrupt */ +#define CAN_ESR1_ERRINTFAST (1 << 20) /* Bit 20: Error Iterrupt for Errors Detected in Data Phase of CAN FD frames */ +#define CAN_ESR1_ERROVR (1 << 21) /* Bit 21: Error Overrun */ + /* Bits 21-25: Reserved */ +#define CAN_ESR1_STFERRFAST (1 << 26) /* Bit 26: Stuffing Error in the Data Phase of CAN FD frames */ +#define CAN_ESR1_FRMERRFAST (1 << 27) /* Bit 27: Form Error in the Data Phase of CAN FD frames */ +#define CAN_ESR1_CRCERRFAST (1 << 28) /* Bit 28: Cyclic Redundancy Check Error in the CRC field of CAN FD frames */ + /* Bit 29: Reserved */ +#define CAN_ESR1_BIT0ERRFAST (1 << 30) /* Bit 30: Bit0 Error in the Data Phase of CAN FD frames */ +#define CAN_ESR1_BIT1ERRFAST (1 << 31) /* Bit 31: Bit1 Error in the Data Phase of CAN FD frames */ +#endif /* Bits 19-31: Reserved for FlexCAN1 and FlexCAN2 */ + +/* Interrupt Masks 2 Register */ + +#define CAN_IMASK2(n) (1 << (n)) /* Bit n: Buffer MBn Mask */ + +/* Interrupt Masks 1 Register */ + +#define CAN_IMASK1(n) (1 << (n)) /* Bit n: Buffer MBn Mask */ + +/* Interrupt Flags 2 Register */ + +#define CAN_IFLAG2(n) (1 << (n)) /* Bit n: Buffer MBn Interrupt */ + +/* Interrupt Flags 1 Register */ + +#define CAN_IFLAG1(n) (1 << (n)) /* Bit n: Buffer MBn Interrupt, n=0..4,8..31 */ + +/* Control 2 Register */ + +#ifdef CONFIG_IMXRT_FLEXCAN3 + /* Bits 0-10: Reserved */ +# define CAN_CTRL2_EDFLTDIS (1 << 11) /* Bit 11: Edge Filter Disable */ +# define CAN_CTRL2_ISOCANFDEN (1 << 12) /* Bit 12: ISO CAN FD Enable */ + /* Bit 13: Reserved */ +# define CAN_CTRL2_PREXCEN (1 << 14) /* Bit 14: Protocol Exception Enable */ +# define CAN_CTRL2_TIMERSRC (1 << 15) /* Bit 15: Timer Source */ +#endif /* Bits 0-15: Reserved for FlexCAN1 and FlexCAN2 */ +#define CAN_CTRL2_EACEN (1 << 16) /* Bit 16: Entire Frame Arbitration Field Comparison Enable (Rx) */ +#define CAN_CTRL2_RRS (1 << 17) /* Bit 17: Remote Request Storing */ +#define CAN_CTRL2_MRP (1 << 18) /* Bit 18: Mailboxes Reception Priority */ +#define CAN_CTRL2_TASD_SHIFT (19) /* Bits 19-23: Tx Arbitration Start Delay */ +#define CAN_CTRL2_TASD_MASK (31 << CAN_CTRL2_TASD_SHIFT) +#define CAN_CTRL2_RFFN_SHIFT (24) /* Bits 24-27: Number of Rx FIFO Filters */ +#define CAN_CTRL2_RFFN_MASK (15 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_8MB (0 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_16MB (1 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_24MB (2 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_32MB (3 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_40MB (4 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_48MB (5 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_56MB (6 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_64MB (7 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_72MB (8 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_80MB (9 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_88MB (10 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_96MB (11 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_104MB (12 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_112MB (13 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_120MB (14 << CAN_CTRL2_RFFN_SHIFT) +# define CAN_CTRL2_RFFN_128MB (15 << CAN_CTRL2_RFFN_SHIFT) +#ifdef CONFIG_IMXRT_FLEXCAN3 + /* Bits 28-29: Reserved */ +# define CAN_CTRL2_BOFFDONEMSK (1 << 30) /* Bit 30: Bus Off Done Interrupt Mask */ +# define CAN_CTRL2_ERRMSKFAST (1 << 31) /* Bit 31: Error Interrupt for Errors Detected in the Data Phase of CAN FD frames */ +#else +# define CAN_CTRL2_WRMFRZ (1 << 28) /* Bit 28: Enable unrestricted write access to FlexCAN memory in Freeze mode */ + /* Bits 29-31: Reserved */ +#endif + +/* Error and Status 2 Register */ + + /* Bits 0-12: Reserved */ +#define CAN_ESR2_IMB (1 << 13) /* Bit 13: Inactive Mailbox */ +#define CAN_ESR2_VPS (1 << 14) /* Bit 14: Valid Priority Status */ + /* Bit 15: Reserved */ +#define CAN_ESR2_LPTM_SHIFT (16) /* Bits 16-22: Lowest Priority Tx Mailbox */ +#define CAN_ESR2_LPTM_MASK (0x7f << CAN_ESR2_LPTM_SHIFT) + /* Bits 23-31: Reserved */ + +/* CRC Register */ + +#define CAN_CRCR_TXCRC_SHIFT (0) /* Bits 0-14: CRC Transmitted */ +#define CAN_CRCR_TXCRC_MASK (0x7fff << CAN_CRCR_TXCRC_SHIFT) + /* Bit 15: Reserved */ +#define CAN_CRCR_MBCRC_SHIFT (16) /* Bits 16-22: CRC Mailbox */ +#define CAN_CRCR_MBCRC_MASK (0x7f << CAN_CRCR_MBCRC_SHIFT) + /* Bits 23-31: Reserved */ + +/* Rx FIFO Global Mask Register (32 Rx FIFO Global Mask Bits) */ + +#define CAN_RXFGMASK(n) (1 << (n)) /* Bit n: Rx FIFO n Global Mask Bit */ + +/* Rx FIFO Information Register */ + + /* Bits 9-31: Reserved */ +#define CAN_RXFIR_IDHIT_SHIFT (0) /* Bits 0-8: Identifier Acceptance Filter Hit Indicator */ +#define CAN_RXFIR_IDHIT_MASK (0x1ff << CAN_RXFIR_IDHIT_SHIFT) + +/* Rx Individual Mask Registers */ + +#define CAN_RXIMR(n) (1 << (n)) /* Bit n: Individual Mask Bits */ + +#ifdef CONFIG_IMXRT_FLEXCAN3 + +/* CAN Bit Timing register */ + +#define CAN_CBT_EPSEG2_SHIFT (0) /* Bits 0-4: Extended Phase Segment 2 */ +#define CAN_CBT_EPSEG2_MASK (0x1f << CAN_CBT_EPSEG2_SHIFT) +#define CAN_CBT_EPSEG2(x) (((uint32_t)(((uint32_t)(x)) << CAN_CBT_EPSEG2_SHIFT)) & CAN_CBT_EPSEG2_MASK) +#define CAN_CBT_EPSEG1_SHIFT (5) /* Bits 5-9: Extended Phase Segment 1 */ +#define CAN_CBT_EPSEG1_MASK (0x1f << CAN_CBT_EPSEG1_SHIFT) +#define CAN_CBT_EPSEG1(x) (((uint32_t)(((uint32_t)(x)) << CAN_CBT_EPSEG1_SHIFT)) & CAN_CBT_EPSEG1_MASK) +#define CAN_CBT_EPROPSEG_SHIFT (10) /* Bits 10-15: Extended Propagation Segment */ +#define CAN_CBT_EPROPSEG_MASK (0x1f << CAN_CBT_EPROPSEG_SHIFT) +#define CAN_CBT_EPROPSEG(x) (((uint32_t)(((uint32_t)(x)) << CAN_CBT_EPROPSEG_SHIFT)) & CAN_CBT_EPROPSEG_MASK) +#define CAN_CBT_ERJW_SHIFT (16) /* Bits 16-20: Extended Resync Jump Width */ +#define CAN_CBT_ERJW_MASK (0x1f << CAN_CBT_ERJW_SHIFT) +#define CAN_CBT_ERJW(x) (((uint32_t)(((uint32_t)(x)) << CAN_CBT_ERJW_SHIFT)) & CAN_CBT_ERJW_MASK) +#define CAN_CBT_EPRESDIV_SHIFT (21) /* Bits 21-30: Extendet Prescaler Division Factor */ +#define CAN_CBT_EPRESDIV_MASK (0x3ff << CAN_CBT_EPRESDIV_SHIFT) +#define CAN_CBT_EPRESDIV(x) (((uint32_t)(((uint32_t)(x)) << CAN_CBT_EPRESDIV_SHIFT)) & CAN_CBT_EPRESDIV_MASK) +#define CAN_CBT_BTF (1 << 31) /* Bit 31: Bit Timing Format Enable */ + +/* CAN FD Control register */ + +#define CAN_FDCTRL_TDCVAL_SHIFT (0) /* Bits 0-5: Transceiver Delay Compensation Value */ +#define CAN_FDCTRL_TDCVAL_MASK (0x3f << CAN_FDCTRL_TDCVAL_SHIFT) + /* Bits 6-7: Reserved */ +#define CAN_FDCTRL_TDCOFF_SHIFT (8) /* Bits 8-12: Transceiver Delay Compensation Offset */ +#define CAN_FDCTRL_TDCOFF_MASK (0x3f << CAN_FDCTRL_TDCOFF_SHIFT) +#define CAN_FDCTRL_TDCOFF(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCTRL_TDCOFF_SHIFT)) & CAN_FDCTRL_TDCOFF_MASK) + /* Bit 13: Reserved */ +#define CAN_FDCTRL_TDCFAIL (1 << 14) /* Bit 14: Transceiver Delay Compensation Fail */ +#define CAN_FDCTRL_TDCEN (1 << 15) /* Bit 15: Transceiver Delay Compensation Enable */ +#define CAN_FDCTRL_MBDSR0_SHIFT (16) /* Bits 16-17: Message Buffer Data Size for Region 0 */ +#define CAN_FDCTRL_MBDSR0_MASK (0x3 << CAN_FDCTRL_MBDSR0_SHIFT) +#define CAN_FDCTRL_MSBSR0(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCTRL_MBDSR0_SHIFT)) & CAN_FDCTRL_MBDSR0_MASK) + /* Bit 18: Reserved */ +#define CAN_FDCTRL_MBDSR1_SHIFT (19) /* Bits 19-20: Message Buffer Data Size for Region 2 */ +#define CAN_FDCTRL_MBDSR1_MASK (0x3 << CAN_FDCTRL_MBDSR1_SHIFT) +#define CAN_FDCTRL_MSBSR1(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCTRL_MBDSR1_SHIFT)) & CAN_FDCTRL_MBDSR1_MASK) + /* Bits 21-30: Reserved */ +#define CAN_FDCTRL_FDRATE (1 << 31) /* Bit 31: Bit Rate Switch Enable */ + +/* CAN FD Bit Timing register */ + +#define CAN_FDCBT_FPSEG2_SHIFT (0) /* Bits 0-2: Fast Phase Segment 2 */ +#define CAN_FDCBT_FPSEG2_MASK (0x7 << CAN_FDCBT_FPSEG2_SHIFT) +#define CAN_FDCBT_FPSEG2(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCBT_FPSEG2_SHIFT)) & CAN_FDCBT_FPSEG2_MASK) + /* Bits 3-4: Reserved */ +#define CAN_FDCBT_FPSEG1_SHIFT (5) /* Bits 5-7: Fast Phase Segment 1 */ +#define CAN_FDCBT_FPSEG1_MASK (0x7 << CAN_FDCBT_FPSEG1_SHIFT) +#define CAN_FDCBT_FPSEG1(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCBT_FPSEG1_SHIFT)) & CAN_FDCBT_FPSEG1_MASK) + /* Bits 8-9: Reserved */ +#define CAN_FDCBT_FPROPSEG_SHIFT (10) /* Bits 10-14: Fast Propagation Segment */ +#define CAN_FDCBT_FPROPSEG_MASK (0x1f << CAN_FDCBT_FPROPSEG_SHIFT) +#define CAN_FDCBT_FPROPSEG(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCBT_FPROPSEG_SHIFT)) & CAN_FDCBT_FPROPSEG_MASK) + /* Bit 15: Reserved */ +#define CAN_FDCBT_FRJW_SHIFT (16) /* Bits 16-18: Fast Propagation Segment */ +#define CAN_FDCBT_FRJW_MASK (0x7 << CAN_FDCBT_FRJW_SHIFT) +#define CAN_FDCBT_FRJW(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCBT_FRJW_SHIFT)) & CAN_FDCBT_FRJW_MASK) + /* Bit 19: Reserved */ +#define CAN_FDCBT_FPRESDIV_SHIFT (20) /* Bits 20-29: Fast Propagation Segment */ +#define CAN_FDCBT_FPRESDIV_MASK (0x3ff << CAN_FDCBT_FPRESDIV_SHIFT) +#define CAN_FDCBT_FPRESDIV(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCBT_FPRESDIV_SHIFT)) & CAN_FDCBT_FPRESDIV_MASK) + /* Bits 30-31: Reserved */ + +/* CAN FD CRC register */ + +#define CAN_FDCRC_FD_TXCRC_SHIFT (0) /* Bits 0-20: Extended Tranmitted CRC value */ +#define CAN_FDCRC_FD_TXCRC_MASK (0x1fffff << CAN_FDCRC_FD_TXCRC_SHIFT) +#define CAN_FDCRC_FD_TXCRC(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCRC_FD_TXCRC_SHIFT)) & CAN_FDCRC_FD_TXCRC_MASK) + /* Bits 21-23: Reserved */ +#define CAN_FDCRC_FD_MBCRC_SHIFT (24) /* Bits 24-30: Extended Tranmitted CRC value */ +#define CAN_FDCRC_FD_MBCRC_MASK (0x7f << CAN_FDCRC_FD_MBCRC_SHIFT) +#define CAN_FDCRC_FD_MBCRC(x) (((uint32_t)(((uint32_t)(x)) << CAN_FDCRC_FD_MBCRC_SHIFT)) & CAN_FDCRC_FD_MBCRC_MASK) + /* Bit 31: Reserved */ + +#endif /* CONFIG_IMXRT_FLEXCAN3 */ + +/* CAN MB TX codes */ +#define CAN_TXMB_INACTIVE 0x8 /* MB is not active. */ +#define CAN_TXMB_ABORT 0x9 /* MB is aborted. */ +#define CAN_TXMB_DATAORREMOTE 0xC /* MB is a TX Data Frame(when MB RTR = 0) or */ + /* MB is a TX Remote Request Frame (when MB RTR = 1). */ +#define CAN_TXMB_TANSWER 0xE /* MB is a TX Response Request Frame from */ + /* an incoming Remote Request Frame. */ +#define CAN_TXMB_NOTUSED 0xF /* Not used.*/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#endif /* __ARCH_ARM_SRC_IMXRT_HARDWARE_IMXRT_FLEXCAN_H */ diff --git a/arch/arm/src/imxrt/hardware/imxrt_iomuxc.h b/arch/arm/src/imxrt/hardware/imxrt_iomuxc.h index 42a9303f37d8b..66037dd7df9f1 100644 --- a/arch/arm/src/imxrt/hardware/imxrt_iomuxc.h +++ b/arch/arm/src/imxrt/hardware/imxrt_iomuxc.h @@ -165,6 +165,9 @@ #define IOMUX_ENET_TX_CLK_DEFAULT (IOMUX_SLEW_FAST | IOMUX_DRIVE_40OHM | IOMUX_SPEED_LOW | \ IOMUX_PULL_DOWN_100K | IOMUX_PULL_KEEP | GPIO_SION_ENABLE ) +#define IOMUX_CAN_DEFAULT (IOMUX_SLEW_SLOW | \ + IOMUX_DRIVE_50OHM | IOMUX_SPEED_LOW ) + #define IOMUX_USDHC1_DATAX_DEFAULT (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | \ IOMUX_PULL_UP_47K | IOMUX_SCHMITT_TRIGGER) #define IOMUX_USDHC1_CMD_DEFAULT (IOMUX_SLEW_FAST | IOMUX_DRIVE_130OHM | \ diff --git a/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_ccm.h b/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_ccm.h index 187ce93c6e9e8..b451f9f55c77e 100644 --- a/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_ccm.h +++ b/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_ccm.h @@ -51,7 +51,7 @@ /* Register offsets *****************************************************************************************/ #define IMXRT_CCM_CCR_OFFSET 0x0000 /* CCM Control Register */ - /* 0x0004 Reserved */ + /* 0x0004 Reserved */ #define IMXRT_CCM_CSR_OFFSET 0x0008 /* CCM Status Register */ #define IMXRT_CCM_CCSR_OFFSET 0x000c /* CCM Clock Switcher Register */ #define IMXRT_CCM_CACRR_OFFSET 0x0010 /* CCM Arm Clock Root Register */ @@ -63,14 +63,14 @@ #define IMXRT_CCM_CS1CDR_OFFSET 0x0028 /* CCM Clock Divider Register */ #define IMXRT_CCM_CS2CDR_OFFSET 0x002c /* CCM Clock Divider Register */ #define IMXRT_CCM_CDCDR_OFFSET 0x0030 /* CCM D1 Clock Divider Register */ - /* 0x0034 Reserved */ + /* 0x0034 Reserved */ #define IMXRT_CCM_CSCDR2_OFFSET 0x0038 /* CCM Serial Clock Divider Register 2 */ #define IMXRT_CCM_CSCDR3_OFFSET 0x003c /* CCM Serial Clock Divider Register 3 */ - /* 0x0040 Reserved */ - /* 0x0044 Reserved */ + /* 0x0040 Reserved */ + /* 0x0044 Reserved */ #define IMXRT_CCM_CDHIPR_OFFSET 0x0048 /* CCM Divider Handshake In-Process Register */ - /* 0x004c Reserved */ - /* 0x0050 Reserved */ + /* 0x004c Reserved */ + /* 0x0050 Reserved */ #define IMXRT_CCM_CLPCR_OFFSET 0x0054 /* CCM Low Power Control Register */ #define IMXRT_CCM_CISR_OFFSET 0x0058 /* CCM Interrupt Status Register */ @@ -84,7 +84,8 @@ #define IMXRT_CCM_CCGR4_OFFSET 0x0078 /* CCM Clock Gating Register 4 */ #define IMXRT_CCM_CCGR5_OFFSET 0x007c /* CCM Clock Gating Register 5 */ #define IMXRT_CCM_CCGR6_OFFSET 0x0080 /* CCM Clock Gating Register 6 */ - /* 0x0084 Reserved */ +#define IMXRT_CCM_CCGR7_OFFSET 0x0084 /* CCM Clock Gating Register 7 */ + /* 0x0084 Reserved */ #define IMXRT_CCM_CMEOR_OFFSET 0x0088 /* CCM Module Enable Override Register */ /* Analog */ @@ -138,6 +139,7 @@ #define IMXRT_CCM_CCGR4 (IMXRT_CCM_BASE + IMXRT_CCM_CCGR4_OFFSET) #define IMXRT_CCM_CCGR5 (IMXRT_CCM_BASE + IMXRT_CCM_CCGR5_OFFSET) #define IMXRT_CCM_CCGR6 (IMXRT_CCM_BASE + IMXRT_CCM_CCGR6_OFFSET) +#define IMXRT_CCM_CCGR7 (IMXRT_CCM_BASE + IMXRT_CCM_CCGR7_OFFSET) #define IMXRT_CCM_CMEOR (IMXRT_CCM_BASE + IMXRT_CCM_CMEOR_OFFSET) #define IMXRT_CCM_ANALOG_PLL_ARM (IMXRT_ANATOP_BASE + IMXRT_CCM_ANALOG_PLL_ARM_OFFSET) @@ -180,6 +182,7 @@ # define CCM_CCR_REG_BYPASS_COUNT(n) ((uint32_t)(n) << CCM_CCR_REG_BYPASS_COUNT_SHIFT) #define CCM_CCR_RBC_EN (1 << 27) /* Bit 27: Enable for REG_BYPASS_COUNTER */ /* Bits 28-31: Reserved */ + /* Status Register */ #define CCM_CSR_REF_EN_B (1 << 0) /* Bit 0: Status of the value of CCM_REF_EN_B */ @@ -188,6 +191,7 @@ /* Bit 4: Reserved */ #define CCM_CSR_COSC_READY (5 << 0) /* Bit 5: Status indication of on board oscillator */ /* Bits 6-31: Reserved */ + /* Clock Switcher Register */ #define CCM_CCSR_PLL3_SW_CLK_SEL (1 << 0) /* Bit 0: Selects source to generate pll3_sw_clk */ @@ -487,6 +491,7 @@ # define CCM_CLPCR_LPM_RUN ((uint32_t)(0) << CCM_CLPCR_LPM_SHIFT) /* Remain in run mode */ # define CCM_CLPCR_LPM_WAIT ((uint32_t)(1) << CCM_CLPCR_LPM_SHIFT) /* Transfer to wait mode */ # define CCM_CLPCR_LPM_STOP ((uint32_t)(2) << CCM_CLPCR_LPM_SHIFT) /* Transfer to stop mode */ + /* Bits 2-4: Reserved */ #define CCM_CLPCR_ARM_CLK_DIS_ON_LPM (1 << 5) /* Bit 5: ARM clocks disabled on wait mode */ #define CCM_CLPCR_SBYOS (1 << 6) /* Bit 6: Standby clock oscillator bit */ @@ -764,6 +769,14 @@ #define CCM_CCGR_USDHC1 IMXRT_CCM_CCGR6, 1 #define CCM_CCGR_USBOH3 IMXRT_CCM_CCGR6, 0 +#define CCM_CCGR_FLEXIO IMXRT_CCM_CCGR7, 6 +#define CCM_CCGR_AIPS IMXRT_CCM_CCGR7, 5 +#define CCM_CCGR_CAN3_SERIAL IMXRT_CCM_CCGR7, 4 +#define CCM_CCGR_CAN3 IMXRT_CCM_CCGR7, 3 +#define CCM_CCGR_AXBS IMXRT_CCM_CCGR7, 2 +#define CCM_CCGR_FLEXSPI2 IMXRT_CCM_CCGR7, 1 +#define CCM_CCGR_ENET2 IMXRT_CCM_CCGR7, 0 + /* Module Enable Override Register */ /* Bits 0-4: Reserved */ @@ -771,7 +784,8 @@ #define CCM_CMEOR_MOD_EN_OV_PIT (1 << 6) /* Bit 6: Override clock enable signal from PIT */ #define CCM_CMEOR_MOD_EN_OV_USDHC (1 << 7) /* Bit 7: Override clock enable signal from USDHC */ #define CCM_CMEOR_MOD_EN_OV_TRNG (1 << 9) /* Bit 9: Override clock enable signal from TRNG */ - /* Bits 10-27: Reserved */ +#define CCM_CMEOR_MOD_EN_OV_CANFD_CPI (1 << 10) /* Bit 10: Override clock enable signal from CAN3 */ + /* Bits 11-27: Reserved */ #define CCM_CMEOR_MOD_EN_OV_CAN2_CPI (1 << 28) /* Bit 28: Override clock enable signal from CAN2 */ #define CCM_CMEOR_MOD_EN_OV_CAN1_CPI (1 << 30) /* Bit 30: Override clock enable signal from CAN1 */ /* Bit 31: Reserved */ @@ -788,7 +802,8 @@ #define CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_MASK (0x3 << CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_SHIFT) # define CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_REF_24M ((uint32_t)(0) << CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_SHIFT) /* Select 24Mhz Osc as source */ # define CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_CLK1 ((uint32_t)(1) << CCM_ANALOG_PLL_ARM_BYPASS_CLK_SRC_SHIFT) /* Select the CLK1_N / CLK1_P as source */ -#define CCM_ANALOG_PLL_ARM_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ +#define CCM_ANALOG_PLL_ARM_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ + /* Bits 17-18 Reserved */ #define CCM_ANALOG_PLL_ARM_PLL_SEL (1 << 39) /* Bit 19: ? */ #define CCM_ANALOG_PLL_ARM_LOCK (1 << 31) /* Bit 31: PLL is currently locked */ @@ -809,7 +824,8 @@ # define CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_CLK1 ((uint32_t)(1) << CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_SHIFT) /* Select the CLK1_N / CLK1_P as source */ # define CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_GPANAIO ((uint32_t)(2) << CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_SHIFT) /* */ # define CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_CHRG_DET_B ((uint32_t)(3) << CCM_ANALOG_PLL_USB1_BYPASS_CLK_SRC_SHIFT) /* */ -#define CCM_ANALOG_PLL_USB1_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ +#define CCM_ANALOG_PLL_USB1_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ + /* Bits 17-30 Reserved */ #define CCM_ANALOG_PLL_USB1_LOCK (1 << 31) /* Bit 31: PLL is currently locked */ @@ -827,7 +843,8 @@ #define CCM_ANALOG_PLL_USB2_BYPASS_CLK_SRC_MASK (0x3 << CCM_ANALOG_PLL_USB2_BYPASS_CLK_SRC_SHIFT) # define CCM_ANALOG_PLL_USB2_BYPASS_CLK_SRC_REF_24M ((uint32_t)(0) << CCM_ANALOG_PLL_USB2_BYPASS_CLK_SRC_SHIFT) /* Select 24Mhz Osc as source */ # define CCM_ANALOG_PLL_USB2_BYPASS_CLK_SRC_CLK1 ((uint32_t)(1) << CCM_ANALOG_PLL_USB2_BYPASS_CLK_SRC_SHIFT) /* Select the CLK1_N / CLK1_P as source */ -#define CCM_ANALOG_PLL_USB2_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ +#define CCM_ANALOG_PLL_USB2_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ + /* Bits 17-30 Reserved */ #define CCM_ANALOG_PLL_USB2_LOCK (1 << 31) /* Bit 31: PLL is currently locked */ @@ -846,9 +863,11 @@ # define CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_CLK1 ((uint32_t)(1) << CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_SHIFT) /* Select the CLK1_N / CLK1_P as source */ # define CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_GPANAIO ((uint32_t)(2) << CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_SHIFT) /* */ # define CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_CHRG_DET_B ((uint32_t)(3) << CCM_ANALOG_PLL_SYS_BYPASS_CLK_SRC_SHIFT) /* */ -#define CCM_ANALOG_PLL_SYS_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ +#define CCM_ANALOG_PLL_SYS_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ + /* Bit 17: Reserved */ #define CCM_ANALOG_PLL_SYS_PFD_OFFSET_EN (1 << 18) /* Bit 18: Enables an offset in the phase frequency detector */ + /* Bits 19-30 Reserved */ #define CCM_ANALOG_PLL_SYS_LOCK (1 << 31) /* Bit 31: PLL is currently locked */ @@ -888,7 +907,8 @@ #define CCM_ANALOG_PLL_AUDIO_BYPASS_CLK_SRC_MASK (0x3 << CCM_ANALOG_PLL_AUDIO_BYPASS_CLK_SRC_SHIFT) # define CCM_ANALOG_PLL_AUDIO_BYPASS_CLK_SRC_REF_24M ((uint32_t)(0) << CCM_ANALOG_PLL_AUDIO_BYPASS_CLK_SRC_SHIFT) /* Select 24Mhz Osc as source */ # define CCM_ANALOG_PLL_AUDIO_BYPASS_CLK_SRC_CLK1 ((uint32_t)(1) << CCM_ANALOG_PLL_AUDIO_BYPASS_CLK_SRC_SHIFT) /* Select the CLK1_N / CLK1_P as source */ -#define CCM_ANALOG_PLL_AUDIO_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ +#define CCM_ANALOG_PLL_AUDIO_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ + /* Bit 17: Reserved */ #define CCM_ANALOG_PLL_AUDIO_PFD_OFFSET_EN (1 << 18) /* Bit 18: Enables an offset in the phase frequency detector */ #define CCM_ANALOG_PLL_AUDIO_POST_DIV_SELECT_SHIFT (19) /* Bits 19-20: These bits implement a divider after the PLL */ @@ -911,7 +931,8 @@ #define CCM_ANALOG_PLL_AUDIO_DENOM_B_SHIFT (0) /* Bits 0-29: 30 bit numerator (A) */ #define CCM_ANALOG_PLL_AUDIO_DENOM_B_MASK (0x3FFFFFFF << CCM_ANALOG_PLL_AUDIO_DENOM_B_SHIFT) #define CCM_ANALOG_PLL_AUDIO_DENOM_B(n) ((uint32_t)(n) << CCM_ANALOG_PLL_AUDIO_DENOM_B_SHIFT) - /* Bits 30-31: Reserved */ + /* Bits 30-31: Reserved */ + /* Analog Video PLL control Register */ #define CCM_ANALOG_PLL_VIDEO_DIV_SELECT_SHIFT (0) /* Bits 0-6: This field controls the PLL loop divider: 27-54 */ @@ -924,7 +945,8 @@ #define CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_MASK (0x3 << CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_SHIFT) # define CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_REF_24M ((uint32_t)(0) << CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_SHIFT) /* Select 24Mhz Osc as source */ # define CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_CLK1 ((uint32_t)(1) << CCM_ANALOG_PLL_VIDEO_BYPASS_CLK_SRC_SHIFT) /* Select the CLK1_N / CLK1_P as source */ -#define CCM_ANALOG_PLL_VIDEO_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ +#define CCM_ANALOG_PLL_VIDEO_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ + /* Bit 17: Reserved */ #define CCM_ANALOG_PLL_VIDEO_PFD_OFFSET_EN (1 << 18) /* Bit 18: Enables an offset in the phase frequency detector */ #define CCM_ANALOG_PLL_VIDEO_POST_DIV_SELECT_SHIFT (19) /* Bits 19-20: These bits implement a divider after the PLL */ @@ -966,11 +988,12 @@ /* Bits 4-11: Reserved */ #define CCM_ANALOG_PLL_ENET_POWERDOWN (1 << 12) /* Bit 12: Powers down the PLL */ #define CCM_ANALOG_PLL_ENET_ENET1_125M_EN (1 << 13) /* Bit 13: Enable the PLL providing the ENET1 125 MHz reference clock */ -#define CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_SHIFT (14) /* Bits 14-15: Determines the bypass source */ +#define CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_SHIFT (14) /* Bits 14-15: Determines the bypass source */ #define CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_MASK (0x3 << CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_SHIFT) # define CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_REF_24M ((uint32_t)(0) << CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_SHIFT) /* Select 24Mhz Osc as source */ # define CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_CLK1 ((uint32_t)(1) << CCM_ANALOG_PLL_ENET_BYPASS_CLK_SRC_SHIFT) /* Select the CLK1_N / CLK1_P as source */ -#define CCM_ANALOG_PLL_ENET_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ +#define CCM_ANALOG_PLL_ENET_BYPASS (1 << 16) /* Bit 16: Bypass the PLL */ + /* Bit 17: Reserved */ #define CCM_ANALOG_PLL_ENET_PFD_OFFSET_EN (1 << 18) /* Bit 18: Enables an offset in the phase frequency detector */ #define CCM_ANALOG_PLL_ENET_ENABLE_125M (1 << 19) /* Bit 19: */ diff --git a/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_pinmux.h b/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_pinmux.h index 8b71af2335292..b5d7eea363c78 100644 --- a/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_pinmux.h +++ b/arch/arm/src/imxrt/hardware/rt106x/imxrt106x_pinmux.h @@ -43,6 +43,7 @@ #include #include "imxrt_iomuxc.h" +#include "imxrt_gpio.h" /***************************************************************************** * Pre-processor Definitions diff --git a/arch/arm/src/imxrt/imxrt_clockconfig.c b/arch/arm/src/imxrt/imxrt_clockconfig.c index 4a94a53de0f76..aed8c6ad34f5e 100644 --- a/arch/arm/src/imxrt/imxrt_clockconfig.c +++ b/arch/arm/src/imxrt/imxrt_clockconfig.c @@ -619,6 +619,25 @@ void imxrt_clockconfig(void) #endif +#ifdef CONFIG_IMXRT_FLEXCAN + /* Set FlexCAN clock source to PLL3 80M */ + + reg = getreg32(IMXRT_CCM_CSCMR2); + reg &= ~CCM_CSCMR2_CAN_CLK_SEL_MASK; + reg |= IMXRT_CAN_CLK_SELECT; + putreg32(reg, IMXRT_CCM_CSCMR2); + + /* Set FlexCAN dividet to 1 for 80 MHz */ + + reg = getreg32(IMXRT_CCM_CSCMR2); + reg &= ~CCM_CSCMR2_CAN_CLK_PODF_MASK; + reg |= CCM_CSCMR2_CAN_CLK_PODF( + CCM_PODF_FROM_DIVISOR(IMXRT_CAN_PODF_DIVIDER) + ); + putreg32(reg, IMXRT_CCM_CSCMR2); + +#endif + #ifdef CONFIG_IMXRT_LPSPI /* Set LPSPI clock source to PLL3 PFD0 */ diff --git a/arch/arm/src/imxrt/imxrt_flexcan.c b/arch/arm/src/imxrt/imxrt_flexcan.c new file mode 100644 index 0000000000000..c6839c61f114b --- /dev/null +++ b/arch/arm/src/imxrt/imxrt_flexcan.c @@ -0,0 +1,1861 @@ +/**************************************************************************** + * arch/arm/src/imxrt/imxrt_flexcan.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "arm_arch.h" +#include "chip.h" +#include "imxrt_config.h" +#include "imxrt_flexcan.h" +#include "imxrt_periphclks.h" +#include "hardware/imxrt_flexcan.h" +#include "hardware/imxrt_pinmux.h" +#include "hardware/imxrt_ccm.h" + +#include + +#ifdef CONFIG_NET_CMSG +#include +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* If processing is not done at the interrupt level, then work queue support + * is required. + */ + +#define CANWORK LPWORK + +/* CONFIG_IMXRT_FLEXCAN_NETHIFS determines the number of physical + * interfaces that will be supported. + */ + +#define MASKSTDID 0x000007ff +#define MASKEXTID 0x1fffffff +#define FLAGEFF (1 << 31) /* Extended frame format */ +#define FLAGRTR (1 << 30) /* Remote transmission request */ + +#define RXMBCOUNT 5 +#define TXMBCOUNT 2 +#define TOTALMBCOUNT RXMBCOUNT + TXMBCOUNT + +#define IFLAG1_RX ((1 << RXMBCOUNT)-1) +#define IFLAG1_TX (((1 << TXMBCOUNT)-1) << RXMBCOUNT) + +#define CAN_FIFO_NE (1 << 5) +#define CAN_FIFO_OV (1 << 6) +#define CAN_FIFO_WARN (1 << 7) +#define CAN_EFF_FLAG 0x80000000 /* EFF/SFF is set in the MSB */ + +#define POOL_SIZE 1 + +#ifdef CONFIG_NET_CMSG +#define MSG_DATA sizeof(struct timeval) +#else +#define MSG_DATA 0 +#endif + +/* CAN bit timing values */ +#define CLK_FREQ 80000000 +#define PRESDIV_MAX 256 + +#define SEG_MAX 8 +#define SEG_MIN 1 +#define TSEG_MIN 2 +#define TSEG1_MAX 17 +#define TSEG2_MAX 9 +#define NUMTQ_MAX 26 + +#define SEG_FD_MAX 32 +#define SEG_FD_MIN 1 +#define TSEG_FD_MIN 2 +#define TSEG1_FD_MAX 39 +#define TSEG2_FD_MAX 9 +#define NUMTQ_FD_MAX 49 + +#ifdef CONFIG_NET_CAN_RAW_TX_DEADLINE + +# if !defined(CONFIG_SCHED_WORKQUEUE) +# error Work queue support is required +# endif + +#define TX_TIMEOUT_WQ +#endif + +/* Interrupt flags for RX fifo */ +#define IFLAG1_RXFIFO (CAN_FIFO_NE | CAN_FIFO_WARN | CAN_FIFO_OV) + +static int peak_tx_mailbox_index_ = 0; + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +union cs_e +{ + volatile uint32_t cs; + struct + { + volatile uint32_t time_stamp : 16; + volatile uint32_t dlc : 4; + volatile uint32_t rtr : 1; + volatile uint32_t ide : 1; + volatile uint32_t srr : 1; + volatile uint32_t res : 1; + volatile uint32_t code : 4; + volatile uint32_t res2 : 1; + volatile uint32_t esi : 1; + volatile uint32_t brs : 1; + volatile uint32_t edl : 1; + }; +}; + +union id_e +{ + volatile uint32_t w; + struct + { + volatile uint32_t ext : 29; + volatile uint32_t resex : 3; + }; + struct + { + volatile uint32_t res : 18; + volatile uint32_t std : 11; + volatile uint32_t resstd : 3; + }; +}; + +union data_e +{ + volatile uint32_t w00; + struct + { + volatile uint32_t b03 : 8; + volatile uint32_t b02 : 8; + volatile uint32_t b01 : 8; + volatile uint32_t b00 : 8; + }; +}; + +struct mb_s +{ + union cs_e cs; + union id_e id; +#ifdef CONFIG_NET_CAN_CANFD + union data_e data[16]; +#else + union data_e data[2]; +#endif +}; + +#ifdef CONFIG_NET_CAN_RAW_TX_DEADLINE +#define TX_ABORT -1 +#define TX_FREE 0 +#define TX_BUSY 1 + +struct txmbstats +{ + struct timeval deadline; + uint32_t pending; /* -1 = abort, 0 = free, 1 = busy */ +}; +#endif + +/* FlexCAN Device hardware configuration */ + +struct flexcan_config_s +{ + uint32_t tx_pin; /* GPIO configuration for TX */ + uint32_t rx_pin; /* GPIO configuration for RX */ + uint32_t irq; /* Combined interrupt */ +}; + +struct flexcan_timeseg +{ + uint32_t bitrate; + int32_t samplep; + uint8_t propseg; + uint8_t pseg1; + uint8_t pseg2; + uint8_t presdiv; +}; + +/* FlexCAN device structures */ + +#ifdef CONFIG_IMXRT_FLEXCAN1 +static const struct flexcan_config_s imxrt_flexcan1_config = +{ + .tx_pin = GPIO_FLEXCAN1_TX, + .rx_pin = GPIO_FLEXCAN1_RX, + .irq = IMXRT_IRQ_CAN1, +}; +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN2 +static const struct flexcan_config_s imxrt_flexcan2_config = +{ + .tx_pin = GPIO_FLEXCAN2_TX, + .rx_pin = GPIO_FLEXCAN2_RX, + .irq = IMXRT_IRQ_CAN2, +}; +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN3 +static const struct flexcan_config_s imxrt_flexcan3_config = +{ + .tx_pin = GPIO_FLEXCAN3_TX, + .rx_pin = GPIO_FLEXCAN3_RX, + .irq = IMXRT_IRQ_CAN3, +}; +#endif + +/* The imxrt_driver_s encapsulates all state information for a single + * hardware interface + */ + +struct imxrt_driver_s +{ + uint32_t base; /* FLEXCAN base address */ + bool bifup; /* true:ifup false:ifdown */ +#ifdef TX_TIMEOUT_WQ + WDOG_ID txtimeout[TXMBCOUNT]; /* TX timeout timer */ +#endif + struct work_s irqwork; /* For deferring interrupt work to the wq */ + struct work_s pollwork; /* For deferring poll work to the work wq */ +#ifdef CONFIG_NET_CAN_CANFD + struct canfd_frame *txdesc; /* A pointer to the list of TX descriptor */ + struct canfd_frame *rxdesc; /* A pointer to the list of RX descriptors */ +#else + struct can_frame *txdesc; /* A pointer to the list of TX descriptor */ + struct can_frame *rxdesc; /* A pointer to the list of RX descriptors */ +#endif + + /* This holds the information visible to the NuttX network */ + + struct net_driver_s dev; /* Interface understood by the network */ + + struct mb_s *rx; + struct mb_s *tx; + + struct flexcan_timeseg arbi_timing; /* Timing for arbitration phase */ +#ifdef CONFIG_NET_CAN_CANFD + struct flexcan_timeseg data_timing; /* Timing for data phase */ +#endif + + const struct flexcan_config_s *config; + +#ifdef CONFIG_NET_CAN_RAW_TX_DEADLINE + struct txmbstats txmb[TXMBCOUNT]; +#endif +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +#ifdef CONFIG_IMXRT_FLEXCAN1 +static struct imxrt_driver_s g_flexcan1; +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN2 +static struct imxrt_driver_s g_flexcan2; +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN3 +static struct imxrt_driver_s g_flexcan3; +#endif + +#ifdef CONFIG_NET_CAN_CANFD +static uint8_t g_tx_pool[(sizeof(struct canfd_frame)+MSG_DATA)*POOL_SIZE]; +static uint8_t g_rx_pool[(sizeof(struct canfd_frame)+MSG_DATA)*POOL_SIZE]; +#else +static uint8_t g_tx_pool[sizeof(struct can_frame)*POOL_SIZE]; +static uint8_t g_rx_pool[sizeof(struct can_frame)*POOL_SIZE]; +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: arm_lsb + * + * Description: + * Calculate position of lsb that's equal to 1 + * + * Input Parameters: + * value - The value to perform the operation on + * + * Returned Value: + * location of lsb which is equal to 1, returns 32 when value is 0 + * + ****************************************************************************/ + +static inline uint32_t arm_lsb(unsigned int value) +{ + uint32_t ret; + volatile uint32_t rvalue = value; + __asm__ __volatile__ ("rbit %1,%0" : "=r" (rvalue) : "r" (rvalue)); + __asm__ __volatile__ ("clz %0, %1" : "=r"(ret) : "r"(rvalue)); + return ret; +} + +/**************************************************************************** + * Name: imxrt_bitratetotimeseg + * + * Description: + * Convert bitrate to timeseg + * + * Input Parameters: + * timeseg - structure to store bit timing + * sp_tolerance - allowed difference in sample point from calculated + * bit timings (recommended value: 1) + * can_fd - if set to calculate CAN FD bit timings, otherwise calculate + * classical can timings + * + * Returned Value: + * return 1 on succes, return 0 on failure + * + ****************************************************************************/ + +uint32_t imxrt_bitratetotimeseg(struct flexcan_timeseg *timeseg, + int32_t sp_tolerance, + uint32_t can_fd) +{ + int32_t tmppresdiv; + int32_t numtq; + int32_t tmpsample; + int32_t tseg1; + int32_t tseg2; + int32_t tmppseg1; + int32_t tmppseg2; + int32_t tmppropseg; + + const int32_t TSEG1MAX = (can_fd ? TSEG1_FD_MAX : TSEG1_MAX); + const int32_t TSEG2MAX = (can_fd ? TSEG2_FD_MAX : TSEG2_MAX); + const int32_t SEGMAX = (can_fd ? SEG_FD_MAX : SEG_MAX); + const int32_t NUMTQMAX = (can_fd ? NUMTQ_FD_MAX : NUMTQ_MAX); + + for (tmppresdiv = 0; tmppresdiv < PRESDIV_MAX; tmppresdiv++) + { + numtq = (CLK_FREQ / ((tmppresdiv + 1) * timeseg->bitrate)); + + if (numtq == 0) + { + continue; + } + + /* The number of time quanta in 1 bit time must be + * lower than the one supported + */ + + if ((CLK_FREQ / ((tmppresdiv + 1) * numtq) == timeseg->bitrate) + && (numtq >= 8) && (numtq < NUMTQMAX)) + { + /* Compute time segments based on the value of the sampling point */ + + tseg1 = (numtq * timeseg->samplep / 100) - 1; + tseg2 = numtq - 1 - tseg1; + + /* Adjust time segment 1 and time segment 2 */ + + while (tseg1 >= TSEG1MAX || tseg2 < TSEG_MIN) + { + tseg2++; + tseg1--; + } + + tmppseg2 = tseg2 - 1; + + /* Start from pseg1 = pseg2 and adjust until propseg is valid */ + + tmppseg1 = tmppseg2; + tmppropseg = tseg1 - tmppseg1 - 2; + + while (tmppropseg <= 0) + { + tmppropseg++; + tmppseg1--; + } + + while (tmppropseg >= SEGMAX) + { + tmppropseg--; + tmppseg1++; + } + + if (((tseg1 >= TSEG1MAX) || (tseg2 >= TSEG2MAX) || + (tseg2 < TSEG_MIN) || (tseg1 < TSEG_MIN)) || + ((tmppropseg >= SEGMAX) || (tmppseg1 >= SEGMAX) || + (tmppseg2 < SEG_MIN) || (tmppseg2 >= SEGMAX))) + { + continue; + } + + tmpsample = ((tseg1 + 1) * 100) / numtq; + + if ((tmpsample - timeseg->samplep) <= sp_tolerance && + (timeseg->samplep - tmpsample) <= sp_tolerance) + { + if (can_fd == 1) + { + timeseg->propseg = tmppropseg + 1; + } + else + { + timeseg->propseg = tmppropseg; + } + timeseg->pseg1 = tmppseg1; + timeseg->pseg2 = tmppseg2; + timeseg->presdiv = tmppresdiv; + timeseg->samplep = tmpsample; + return 1; + } + } + } + + return 0; +} + +/* Common TX logic */ + +static bool imxrt_txringfull(FAR struct imxrt_driver_s *priv); +static int imxrt_transmit(FAR struct imxrt_driver_s *priv); +static int imxrt_txpoll(struct net_driver_s *dev); + +/* Helper functions */ + +static void imxrt_setenable(uint32_t base, uint32_t enable); +static void imxrt_setfreeze(uint32_t base, uint32_t freeze); +static uint32_t imxrt_waitmcr_change(uint32_t base, + uint32_t mask, + uint32_t target_state); + +/* Interrupt handling */ + +static void imxrt_receive(FAR struct imxrt_driver_s *priv, + uint32_t flags); +static void imxrt_txdone(FAR void *arg); + +static int imxrt_flexcan_interrupt(int irq, FAR void *context, + FAR void *arg); + +/* Watchdog timer expirations */ +#ifdef TX_TIMEOUT_WQ +static void imxrt_txtimeout_work(FAR void *arg); +static void imxrt_txtimeout_expiry(int argc, uint32_t arg, ...); +#endif + +/* NuttX callback functions */ + +static int imxrt_ifup(struct net_driver_s *dev); +static int imxrt_ifdown(struct net_driver_s *dev); + +static void imxrt_txavail_work(FAR void *arg); +static int imxrt_txavail(struct net_driver_s *dev); + +#ifdef CONFIG_NETDEV_IOCTL +static int imxrt_ioctl(struct net_driver_s *dev, int cmd, + unsigned long arg); +#endif + +/* Initialization */ + +static int imxrt_initialize(struct imxrt_driver_s *priv); +static void imxrt_reset(struct imxrt_driver_s *priv); + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: imxrt_txringfull + * + * Description: + * Check if all of the TX descriptors are in use. + * + * Input Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * true is the TX ring is full; false if there are free slots at the + * head index. + * + ****************************************************************************/ + +static bool imxrt_txringfull(FAR struct imxrt_driver_s *priv) +{ + uint32_t mbi = 0; + + while (mbi < TXMBCOUNT) + { + if (priv->tx[mbi].cs.code != CAN_TXMB_DATAORREMOTE) + { + return 0; + } + + mbi++; + } + + return 1; +} + +/**************************************************************************** + * Function: imxrt_transmit + * + * Description: + * Start hardware transmission. Called either from the txdone interrupt + * handling or from watchdog based polling. + * + * Input Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * OK on success; a negated errno on failure + * + * Assumptions: + * May or may not be called from an interrupt handler. In either case, + * global interrupts are disabled, either explicitly or indirectly through + * interrupt handling logic. + * + ****************************************************************************/ + +static int imxrt_transmit(FAR struct imxrt_driver_s *priv) +{ + /* Attempt to write frame */ + + uint32_t mbi = 0; + uint32_t mb_bit; + uint32_t regval; +#ifdef CONFIG_NET_CAN_CANFD + uint32_t *frame_data_word; + uint32_t i; +#endif +#ifdef CONFIG_NET_CAN_RAW_TX_DEADLINE + int32_t timeout; +#endif + + if ((getreg32(priv->base + IMXRT_CAN_ESR2_OFFSET) & + (CAN_ESR2_IMB | CAN_ESR2_VPS)) == + (CAN_ESR2_IMB | CAN_ESR2_VPS)) + { + mbi = ((getreg32(priv->base + IMXRT_CAN_ESR2_OFFSET) & + CAN_ESR2_LPTM_MASK) >> CAN_ESR2_LPTM_SHIFT); + mbi -= RXMBCOUNT; + } + + mb_bit = 1 << (RXMBCOUNT + mbi); + + while (mbi < TXMBCOUNT) + { + if (priv->tx[mbi].cs.code != CAN_TXMB_DATAORREMOTE) + { + putreg32(mb_bit, priv->base + IMXRT_CAN_IFLAG1_OFFSET); + break; + } + + mb_bit <<= 1; + mbi++; + } + + if (mbi == TXMBCOUNT) + { + nwarn("No TX MB available mbi %i\r\n", mbi); + return 0; /* No transmission for you! */ + } + +#ifdef CONFIG_NET_CAN_RAW_TX_DEADLINE + struct timespec ts; + clock_systimespec(&ts); + + if (priv->dev.d_sndlen > priv->dev.d_len) + { + struct timeval *tv = + (struct timeval *)(priv->dev.d_buf + priv->dev.d_len); + priv->txmb[mbi].deadline = *tv; + timeout = (tv->tv_sec - ts.tv_sec)*CLK_TCK + + ((tv->tv_usec - ts.tv_nsec / 1000)*CLK_TCK) / 1000000; + if (timeout < 0) + { + return 0; /* No transmission for you! */ + } + } + else + { + /* Default TX deadline defined in NET_CAN_RAW_DEFAULT_TX_DEADLINE */ + + if (CONFIG_NET_CAN_RAW_DEFAULT_TX_DEADLINE > 0) + { + timeout = ((CONFIG_NET_CAN_RAW_DEFAULT_TX_DEADLINE / 1000000) + *CLK_TCK); + priv->txmb[mbi].deadline.tv_sec = ts.tv_sec + + CONFIG_NET_CAN_RAW_DEFAULT_TX_DEADLINE / 1000000; + priv->txmb[mbi].deadline.tv_usec = (ts.tv_nsec / 1000) + + CONFIG_NET_CAN_RAW_DEFAULT_TX_DEADLINE % 1000000; + } + else + { + priv->txmb[mbi].deadline.tv_sec = 0; + priv->txmb[mbi].deadline.tv_usec = 0; + timeout = -1; + } + } +#endif + + peak_tx_mailbox_index_ = + (peak_tx_mailbox_index_ > mbi ? peak_tx_mailbox_index_ : mbi); + + union cs_e cs; + cs.code = CAN_TXMB_DATAORREMOTE; + struct mb_s *mb = &priv->tx[mbi]; + mb->cs.code = CAN_TXMB_INACTIVE; + + if (priv->dev.d_len == sizeof(struct can_frame)) + { + struct can_frame *frame = (struct can_frame *)priv->dev.d_buf; + + if (frame->can_id & CAN_EFF_FLAG) + { + cs.ide = 1; + mb->id.ext = frame->can_id & MASKEXTID; + } + else + { + mb->id.std = frame->can_id & MASKSTDID; + } + + cs.rtr = frame->can_id & FLAGRTR ? 1 : 0; + cs.dlc = frame->can_dlc; + + mb->data[0].w00 = __builtin_bswap32(*(uint32_t *)&frame->data[0]); + mb->data[1].w00 = __builtin_bswap32(*(uint32_t *)&frame->data[4]); + } +#ifdef CONFIG_NET_CAN_CANFD + else /* CAN FD frame */ + { + struct canfd_frame *frame = (struct canfd_frame *)priv->dev.d_buf; + + cs.edl = 1; /* CAN FD Frame */ + + if (frame->can_id & CAN_EFF_FLAG) + { + cs.ide = 1; + mb->id.ext = frame->can_id & MASKEXTID; + } + else + { + mb->id.std = frame->can_id & MASKSTDID; + } + + cs.rtr = frame->can_id & FLAGRTR ? 1 : 0; + + cs.dlc = len_to_can_dlc[frame->len]; + + frame_data_word = (uint32_t *)&frame->data[0]; + + for (i = 0; i < (frame->len + 4 - 1) / 4; i++) + { + mb->data[i].w00 = __builtin_bswap32(frame_data_word[i]); + } + } +#endif + + mb->cs = cs; /* Go. */ + + regval = getreg32(priv->base + IMXRT_CAN_IMASK1_OFFSET); + regval |= mb_bit; + putreg32(regval, priv->base + IMXRT_CAN_IMASK1_OFFSET); + + /* Increment statistics */ + + NETDEV_TXPACKETS(&priv->dev); + +#ifdef TX_TIMEOUT_WQ + /* Setup the TX timeout watchdog (perhaps restarting the timer) */ + + if (timeout > 0) + { + wd_start(priv->txtimeout[mbi], timeout + 1, imxrt_txtimeout_expiry, + 1, (wdparm_t)priv); + } +#endif + + return OK; +} + +/**************************************************************************** + * Function: imxrt_txpoll + * + * Description: + * The transmitter is available, check if the network has any outgoing + * packets ready to send. This is a callback from devif_poll(). + * devif_poll() may be called: + * + * 1. When the preceding TX packet send is complete, + * 2. When the preceding TX packet send timesout and the interface is reset + * 3. During normal TX polling + * + * Input Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * OK on success; a negated errno on failure + * + * Assumptions: + * May or may not be called from an interrupt handler. In either case, + * global interrupts are disabled, either explicitly or indirectly through + * interrupt handling logic. + * + ****************************************************************************/ + +static int imxrt_txpoll(struct net_driver_s *dev) +{ + FAR struct imxrt_driver_s *priv = + (FAR struct imxrt_driver_s *)dev->d_private; + + /* If the polling resulted in data that should be sent out on the network, + * the field d_len is set to a value > 0. + */ + + if (priv->dev.d_len > 0) + { + if (!devif_loopback(&priv->dev)) + { + /* Send the packet */ + + imxrt_transmit(priv); + + /* Check if there is room in the device to hold another packet. If + * not, return a non-zero value to terminate the poll. + */ + + if (imxrt_txringfull(priv)) + { + return -EBUSY; + } + } + } + + /* If zero is returned, the polling will continue until all connections + * have been examined. + */ + + return 0; +} + +/**************************************************************************** + * Function: imxrt_receive + * + * Description: + * An interrupt was received indicating the availability of a new RX packet + * + * Input Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * Global interrupts are disabled by interrupt handling logic. + * + ****************************************************************************/ + +static void imxrt_receive(FAR struct imxrt_driver_s *priv, + uint32_t flags) +{ + uint32_t mb_index; + struct mb_s *rf; +#ifdef CONFIG_NET_CAN_CANFD + uint32_t *frame_data_word; + uint32_t i; +#endif + + while ((mb_index = arm_lsb(flags)) != 32) + { + rf = &priv->rx[mb_index]; + + /* Read the frame contents */ + +#ifdef CONFIG_NET_CAN_CANFD + if (rf->cs.edl) /* CAN FD frame */ + { + struct canfd_frame *frame = (struct canfd_frame *)priv->rxdesc; + + if (rf->cs.ide) + { + frame->can_id = MASKEXTID & rf->id.ext; + frame->can_id |= FLAGEFF; + } + else + { + frame->can_id = MASKSTDID & rf->id.std; + } + + if (rf->cs.rtr) + { + frame->can_id |= FLAGRTR; + } + + frame->len = can_dlc_to_len[rf->cs.dlc]; + + frame_data_word = (uint32_t *)&frame->data[0]; + + for (i = 0; i < (frame->len + 4 - 1) / 4; i++) + { + frame_data_word[i] = __builtin_bswap32(rf->data[i].w00); + } + + /* Clear MB interrupt flag */ + + putreg32(1 << mb_index, + priv->base + IMXRT_CAN_IFLAG1_OFFSET); + + /* Copy the buffer pointer to priv->dev.. Set amount of data + * in priv->dev.d_len + */ + + priv->dev.d_len = sizeof(struct canfd_frame); + priv->dev.d_buf = (uint8_t *)frame; + } + else /* CAN 2.0 Frame */ +#endif + { + struct can_frame *frame = (struct can_frame *)priv->rxdesc; + + if (rf->cs.ide) + { + frame->can_id = MASKEXTID & rf->id.ext; + frame->can_id |= FLAGEFF; + } + else + { + frame->can_id = MASKSTDID & rf->id.std; + } + + if (rf->cs.rtr) + { + frame->can_id |= FLAGRTR; + } + + frame->can_dlc = rf->cs.dlc; + + *(uint32_t *)&frame->data[0] = __builtin_bswap32(rf->data[0].w00); + *(uint32_t *)&frame->data[4] = __builtin_bswap32(rf->data[1].w00); + + /* Clear MB interrupt flag */ + + putreg32(1 << mb_index, + priv->base + IMXRT_CAN_IFLAG1_OFFSET); + + /* Copy the buffer pointer to priv->dev.. Set amount of data + * in priv->dev.d_len + */ + + priv->dev.d_len = sizeof(struct can_frame); + priv->dev.d_buf = (uint8_t *)frame; + } + + /* Send to socket interface */ + + NETDEV_RXPACKETS(&priv->dev); + + can_input(&priv->dev); + + /* Point the packet buffer back to the next Tx buffer that will be + * used during the next write. If the write queue is full, then + * this will point at an active buffer, which must not be written + * to. This is OK because devif_poll won't be called unless the + * queue is not full. + */ + + priv->dev.d_buf = (uint8_t *)priv->txdesc; + + flags &= ~(1 << mb_index); + + /* Reread interrupt flags and process them in this loop */ + + if (flags == 0) + { + flags = getreg32(priv->base + IMXRT_CAN_IFLAG1_OFFSET); + flags &= IFLAG1_RX; + } + } +} + +/**************************************************************************** + * Function: imxrt_txdone + * + * Description: + * An interrupt was received indicating that the last TX packet(s) is done + * + * Input Parameters: + * priv - Reference to the driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * Global interrupts are disabled by the watchdog logic. + * We are not in an interrupt context so that we can lock the network. + * + ****************************************************************************/ + +static void imxrt_txdone(FAR void *arg) +{ + FAR struct imxrt_driver_s *priv = (FAR struct imxrt_driver_s *)arg; + uint32_t flags; + uint32_t mbi; + uint32_t mb_bit; + + flags = getreg32(priv->base + IMXRT_CAN_IFLAG1_OFFSET); + flags &= IFLAG1_TX; + + /* TODO First Process Error aborts */ + + /* Process TX completions */ + + mb_bit = 1 << RXMBCOUNT; + for (mbi = 0; flags && mbi < TXMBCOUNT; mbi++) + { + if (flags & mb_bit) + { + putreg32(mb_bit, priv->base + IMXRT_CAN_IFLAG1_OFFSET); + flags &= ~mb_bit; + NETDEV_TXDONE(&priv->dev); +#ifdef TX_TIMEOUT_WQ + /* We are here because a transmission completed, so the + * corresponding watchdog can be canceled. + */ + + wd_cancel(priv->txtimeout[mbi]); +#endif + } + + mb_bit <<= 1; + } + + /* There should be space for a new TX in any event. Poll the network for + * new XMIT data + */ + + net_lock(); + devif_poll(&priv->dev, imxrt_txpoll); + net_unlock(); +} + +/**************************************************************************** + * Function: imxrt_flexcan_interrupt + * + * Description: + * Three interrupt sources will vector this this function: + * 1. CAN MB transmit interrupt handler + * 2. CAN MB receive interrupt handler + * 3. + * + * Input Parameters: + * irq - Number of the IRQ that generated the interrupt + * context - Interrupt register state save info (architecture-specific) + * + * Returned Value: + * OK on success + * + * Assumptions: + * + ****************************************************************************/ + +static int imxrt_flexcan_interrupt(int irq, FAR void *context, + FAR void *arg) +{ + FAR struct imxrt_driver_s *priv = (struct imxrt_driver_s *)arg; + + if (irq == priv->config->irq) + { + uint32_t flags; + flags = getreg32(priv->base + IMXRT_CAN_IFLAG1_OFFSET); + flags &= IFLAG1_RX; + + if (flags) + { + /* Process immediately since scheduling a workqueue is too slow + * which causes us to drop CAN frames + */ + + imxrt_receive(priv, flags); + } + + flags = getreg32(priv->base + IMXRT_CAN_IFLAG1_OFFSET); + flags &= IFLAG1_TX; + + if (flags) + { + /* Disable further TX MB CAN interrupts. here can be no race + * condition here. + */ + + flags = getreg32(priv->base + IMXRT_CAN_IMASK1_OFFSET); + flags &= ~(IFLAG1_TX); + putreg32(flags, priv->base + IMXRT_CAN_IMASK1_OFFSET); + work_queue(CANWORK, &priv->irqwork, imxrt_txdone, priv, 0); + } + } + + return OK; +} + +/**************************************************************************** + * Function: imxrt_txtimeout_work + * + * Description: + * Perform TX timeout related work from the worker thread + * + * Input Parameters: + * arg - The argument passed when work_queue() as called. + * + * Returned Value: + * OK on success + * + * Assumptions: + * + ****************************************************************************/ +#ifdef TX_TIMEOUT_WQ + +static void imxrt_txtimeout_work(FAR void *arg) +{ + FAR struct imxrt_driver_s *priv = (FAR struct imxrt_driver_s *)arg; + uint32_t mbi; + + struct timespec ts; + struct timeval *now = (struct timeval *)&ts; + clock_systimespec(&ts); + now->tv_usec = ts.tv_nsec / 1000; /* timespec to timeval conversion */ + + /* The watchdog timed out, yet we still check mailboxes in case the + * transmit function transmitted a new frame + */ + + for (mbi = 0; mbi < TXMBCOUNT; mbi++) + { + if (priv->txmb[mbi].deadline.tv_sec != 0 + && (now->tv_sec > priv->txmb[mbi].deadline.tv_sec + || now->tv_usec > priv->txmb[mbi].deadline.tv_usec)) + { + NETDEV_TXTIMEOUTS(&priv->dev); + struct mb_s *mb = &priv->tx[mbi]; + mb->cs.code = CAN_TXMB_ABORT; + priv->txmb[mbi].pending = TX_ABORT; + } + } +} + +/**************************************************************************** + * Function: imxrt_txtimeout_expiry + * + * Description: + * Our TX watchdog timed out. Called from the timer interrupt handler. + * The last TX never completed. Reset the hardware and start again. + * + * Input Parameters: + * argc - The number of available arguments + * arg - The first argument + * + * Returned Value: + * None + * + * Assumptions: + * Global interrupts are disabled by the watchdog logic. + * + ****************************************************************************/ + +static void imxrt_txtimeout_expiry(int argc, uint32_t arg, ...) +{ + FAR struct imxrt_driver_s *priv = (FAR struct imxrt_driver_s *)arg; + + /* Schedule to perform the TX timeout processing on the worker thread + */ + + work_queue(CANWORK, &priv->irqwork, imxrt_txtimeout_work, priv, 0); +} + +#endif + +static void imxrt_setenable(uint32_t base, uint32_t enable) +{ + uint32_t regval; + + if (enable) + { + regval = getreg32(base + IMXRT_CAN_MCR_OFFSET); + regval &= ~(CAN_MCR_MDIS); + putreg32(regval, base + IMXRT_CAN_MCR_OFFSET); + } + else + { + regval = getreg32(base + IMXRT_CAN_MCR_OFFSET); + regval |= CAN_MCR_MDIS; + putreg32(regval, base + IMXRT_CAN_MCR_OFFSET); + } + + imxrt_waitmcr_change(base, CAN_MCR_LPMACK, 1); +} + +static void imxrt_setfreeze(uint32_t base, uint32_t freeze) +{ + uint32_t regval; + if (freeze) + { + /* Enter freeze mode */ + + regval = getreg32(base + IMXRT_CAN_MCR_OFFSET); + regval |= (CAN_MCR_HALT | CAN_MCR_FRZ); + putreg32(regval, base + IMXRT_CAN_MCR_OFFSET); + } + else + { + /* Exit freeze mode */ + + regval = getreg32(base + IMXRT_CAN_MCR_OFFSET); + regval &= ~(CAN_MCR_HALT | CAN_MCR_FRZ); + putreg32(regval, base + IMXRT_CAN_MCR_OFFSET); + } +} + +static uint32_t imxrt_waitmcr_change(uint32_t base, uint32_t mask, + uint32_t target_state) +{ + const uint32_t timeout = 1000; + uint32_t wait_ack; + + for (wait_ack = 0; wait_ack < timeout; wait_ack++) + { + const bool state = (getreg32(base + IMXRT_CAN_MCR_OFFSET) & mask) + != 0; + if (state == target_state) + { + return true; + } + + up_udelay(10); + } + + return false; +} + +static uint32_t imxrt_waitfreezeack_change(uint32_t base, + uint32_t target_state) +{ + return imxrt_waitmcr_change(base, CAN_MCR_FRZACK, target_state); +} + +/**************************************************************************** + * Function: imxrt_ifup + * + * Description: + * NuttX Callback: Bring up the Ethernet interface when an IP address is + * provided + * + * Input Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int imxrt_ifup(struct net_driver_s *dev) +{ + FAR struct imxrt_driver_s *priv = + (FAR struct imxrt_driver_s *)dev->d_private; + + if (!imxrt_initialize(priv)) + { + nerr("initialize failed"); + return -1; + } + + priv->bifup = true; + +#ifdef CONFIG_NET_CAN_CANFD + priv->txdesc = (struct canfd_frame *)&g_tx_pool; + priv->rxdesc = (struct canfd_frame *)&g_rx_pool; +#else + priv->txdesc = (struct can_frame *)&g_tx_pool; + priv->rxdesc = (struct can_frame *)&g_rx_pool; +#endif + + priv->dev.d_buf = (uint8_t *)priv->txdesc; + + /* Set interrupts */ + + up_enable_irq(priv->config->irq); + + return OK; +} + +/**************************************************************************** + * Function: imxrt_ifdown + * + * Description: + * NuttX Callback: Stop the interface. + * + * Input Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int imxrt_ifdown(struct net_driver_s *dev) +{ + FAR struct imxrt_driver_s *priv = + (FAR struct imxrt_driver_s *)dev->d_private; + + imxrt_reset(priv); + + priv->bifup = false; + return OK; +} + +/**************************************************************************** + * Function: imxrt_txavail_work + * + * Description: + * Perform an out-of-cycle poll on the worker thread. + * + * Input Parameters: + * arg - Reference to the NuttX driver state structure (cast to void*) + * + * Returned Value: + * None + * + * Assumptions: + * Called on the higher priority worker thread. + * + ****************************************************************************/ + +static void imxrt_txavail_work(FAR void *arg) +{ + FAR struct imxrt_driver_s *priv = (FAR struct imxrt_driver_s *)arg; + + /* Ignore the notification if the interface is not yet up */ + + net_lock(); + if (priv->bifup) + { + /* Check if there is room in the hardware to hold another outgoing + * packet. + */ + + if (!imxrt_txringfull(priv)) + { + /* No, there is space for another transfer. Poll the network for + * new XMIT data. + */ + + devif_poll(&priv->dev, imxrt_txpoll); + } + } + + net_unlock(); +} + +/**************************************************************************** + * Function: imxrt_txavail + * + * Description: + * Driver callback invoked when new TX data is available. This is a + * stimulus perform an out-of-cycle poll and, thereby, reduce the TX + * latency. + * + * Input Parameters: + * dev - Reference to the NuttX driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * Called in normal user mode + * + ****************************************************************************/ + +static int imxrt_txavail(struct net_driver_s *dev) +{ + FAR struct imxrt_driver_s *priv = + (FAR struct imxrt_driver_s *)dev->d_private; + + /* Is our single work structure available? It may not be if there are + * pending interrupt actions and we will have to ignore the Tx + * availability action. + */ + + if (work_available(&priv->pollwork)) + { + /* Schedule to serialize the poll on the worker thread. */ + + imxrt_txavail_work(priv); + } + + return OK; +} + +/**************************************************************************** + * Function: imxrt_ioctl + * + * Description: + * PHY ioctl command handler + * + * Input Parameters: + * dev - Reference to the NuttX driver state structure + * cmd - ioctl command + * arg - Argument accompanying the command + * + * Returned Value: + * Zero (OK) on success; a negated errno value on failure. + * + * Assumptions: + * + ****************************************************************************/ + +#ifdef CONFIG_NETDEV_CAN_BITRATE_IOCTL +static int imxrt_ioctl(struct net_driver_s *dev, int cmd, + unsigned long arg) +{ + FAR struct imxrt_driver_s *priv = + (FAR struct imxrt_driver_s *)dev->d_private; + + int ret; + + switch (cmd) + { + case SIOCGCANBITRATE: /* Get bitrate from a CAN controller */ + { + struct can_ioctl_data_s *req = + (struct can_ioctl_data_s *)((uintptr_t)arg); + req->arbi_bitrate = priv->arbi_timing.bitrate / 1000; /* kbit/s */ + req->arbi_samplep = priv->arbi_timing.samplep; +#ifdef CONFIG_NET_CAN_CANFD + req->data_bitrate = priv->data_timing.bitrate / 1000; /* kbit/s */ + req->data_samplep = priv->data_timing.samplep; +#else + req->data_bitrate = 0; + req->data_samplep = 0; +#endif + ret = OK; + } + break; + + case SIOCSCANBITRATE: /* Set bitrate of a CAN controller */ + { + struct can_ioctl_data_s *req = + (struct can_ioctl_data_s *)((uintptr_t)arg); + + struct flexcan_timeseg arbi_timing; + arbi_timing.bitrate = req->arbi_bitrate * 1000; + arbi_timing.samplep = req->arbi_samplep; + + if (imxrt_bitratetotimeseg(&arbi_timing, 10, 0)) + { + ret = OK; + } + else + { + ret = -EINVAL; + } + +#ifdef CONFIG_NET_CAN_CANFD + struct flexcan_timeseg data_timing; + data_timing.bitrate = req->data_bitrate * 1000; + data_timing.samplep = req->data_samplep; + + if (ret == OK && imxrt_bitratetotimeseg(&data_timing, 10, 1)) + { + ret = OK; + } + else + { + ret = -EINVAL; + } +#endif + + if (ret == OK) + { + /* Reset CAN controller and start with new timings */ + + priv->arbi_timing = arbi_timing; +#ifdef CONFIG_NET_CAN_CANFD + priv->data_timing = data_timing; +#endif + imxrt_ifup(dev); + } + } + break; + + default: + ret = -ENOTTY; + break; + } + + return ret; +} +#endif /* CONFIG_NETDEV_IOCTL */ + +/**************************************************************************** + * Function: imxrt_initalize + * + * Description: + * Initialize FLEXCAN device + * + * Input Parameters: + * priv - Reference to the private FLEXCAN driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static int imxrt_initialize(struct imxrt_driver_s *priv) +{ + uint32_t regval; + uint32_t i; + + /* initialize CAN device */ + +#ifdef CONFIG_IMXRT_FLEXCAN3 + imxrt_setenable(priv->base, 0); + + /* Set SYS_CLOCK src */ + + regval = getreg32(priv->base + IMXRT_CAN_CTRL1_OFFSET); + regval |= (CAN_CTRL1_CLKSRC); + putreg32(regval, priv->base + IMXRT_CAN_CTRL1_OFFSET); +#endif + + imxrt_setenable(priv->base, 1); + + imxrt_reset(priv); + + /* Enter freeze mode */ + + imxrt_setfreeze(priv->base, 1); + if (!imxrt_waitfreezeack_change(priv->base, 1)) + { + ninfo("FLEXCAN: freeze fail\r\n"); + return -1; + } + +#ifndef CONFIG_NET_CAN_CANFD + regval = getreg32(priv->base + IMXRT_CAN_CTRL1_OFFSET); + regval &= ~(CAN_CTRL1_PRESDIV_MASK | CAN_CTRL1_PROPSEG_MASK | + CAN_CTRL1_PSEG1_MASK | CAN_CTRL1_PSEG2_MASK | + CAN_CTRL1_RJW_MASK); + regval |= CAN_CTRL1_PRESDIV(priv->arbi_timing.presdiv) | /* Prescaler divisor factor */ + CAN_CTRL1_PROPSEG(priv->arbi_timing.propseg) | /* Propagation segment */ + CAN_CTRL1_PSEG1(priv->arbi_timing.pseg1) | /* Phase buffer segment 1 */ + CAN_CTRL1_PSEG2(priv->arbi_timing.pseg2) | /* Phase buffer segment 2 */ + CAN_CTRL1_RJW(1); /* Resynchronization jump width */ + putreg32(regval, priv->base + IMXRT_CAN_CTRL1_OFFSET); + +#else + regval = getreg32(priv->base + IMXRT_CAN_CBT_OFFSET); + regval &= ~(CAN_CBT_EPRESDIV_MASK | CAN_CBT_EPROPSEG_MASK | + CAN_CBT_EPSEG1_MASK | CAN_CBT_EPSEG2_MASK | + CAN_CBT_ERJW_MASK); + regval |= CAN_CBT_BTF | /* Enable extended bit timing + * configurations for CAN-FD for setting up + * separately nominal and data phase */ + CAN_CBT_EPRESDIV(priv->arbi_timing.presdiv) | /* Prescaler divisor factor */ + CAN_CBT_EPROPSEG(priv->arbi_timing.propseg) | /* Propagation segment */ + CAN_CBT_EPSEG1(priv->arbi_timing.pseg1) | /* Phase buffer segment 1 */ + CAN_CBT_EPSEG2(priv->arbi_timing.pseg2) | /* Phase buffer segment 2 */ + CAN_CBT_ERJW(1); /* Resynchronization jump width */ + putreg32(regval, priv->base + IMXRT_CAN_CBT_OFFSET); + + /* Enable CAN FD feature */ + + regval = getreg32(priv->base + IMXRT_CAN_MCR_OFFSET); + regval |= CAN_MCR_FDEN; + putreg32(regval, priv->base + IMXRT_CAN_MCR_OFFSET); + + regval = getreg32(priv->base + IMXRT_CAN_FDCBT_OFFSET); + regval &= ~(CAN_FDCBT_FPRESDIV_MASK | CAN_FDCBT_FPROPSEG_MASK | + CAN_FDCBT_FPSEG1_MASK | CAN_FDCBT_FPSEG2_MASK | + CAN_FDCBT_FRJW_MASK); + regval |= CAN_FDCBT_FPRESDIV(priv->data_timing.presdiv) | /* Prescaler divisor factor of 1 */ + CAN_FDCBT_FPROPSEG(priv->data_timing.propseg) | /* Propagation + * segment (only register that doesn't add 1) */ + CAN_FDCBT_FPSEG1(priv->data_timing.pseg1) | /* Phase buffer segment 1 */ + CAN_FDCBT_FPSEG2(priv->data_timing.pseg2) | /* Phase buffer segment 2 */ + CAN_FDCBT_FRJW(priv->data_timing.pseg2); /* Resynchorinzation jump width same as PSEG2 */ + putreg32(regval, priv->base + IMXRT_CAN_FDCBT_OFFSET); + + /* Additional CAN-FD configurations */ + + regval = getreg32(priv->base + IMXRT_CAN_FDCTRL_OFFSET); + + regval |= CAN_FDCTRL_FDRATE | /* Enable bit rate switch in data phase of frame */ + CAN_FDCTRL_TDCEN | /* Enable transceiver delay compensation */ + CAN_FDCTRL_TDCOFF(5) | /* Setup 5 cycles for data phase sampling delay */ + CAN_FDCTRL_MSBSR0(3); /* Setup 64 bytes per message buffer (7 MB's) */ + putreg32(regval, priv->base + IMXRT_CAN_FDCTRL_OFFSET); + + regval = getreg32(priv->base + IMXRT_CAN_CTRL2_OFFSET); + regval |= CAN_CTRL2_ISOCANFDEN; + putreg32(regval, priv->base + IMXRT_CAN_CTRL2_OFFSET); +#endif + + for (i = TXMBCOUNT; i < TOTALMBCOUNT; i++) + { + priv->rx[i].id.w = 0x0; + + /* FIXME sometimes we get a hard fault here */ + } + + putreg32(0x0, priv->base + IMXRT_CAN_RXFGMASK_OFFSET); + + for (i = 0; i < TOTALMBCOUNT; i++) + { + putreg32(0, priv->base + IMXRT_CAN_RXIMR_OFFSET(i)); + } + + for (i = 0; i < RXMBCOUNT; i++) + { + ninfo("Set MB%i to receive %p\r\n", i, &priv->rx[i]); + priv->rx[i].cs.edl = 0x1; + priv->rx[i].cs.brs = 0x1; + priv->rx[i].cs.esi = 0x0; + priv->rx[i].cs.code = 4; + priv->rx[i].cs.srr = 0x0; + priv->rx[i].cs.ide = 0x1; + priv->rx[i].cs.rtr = 0x0; + } + + putreg32(IFLAG1_RX, priv->base + IMXRT_CAN_IFLAG1_OFFSET); + putreg32(IFLAG1_RX, priv->base + IMXRT_CAN_IMASK1_OFFSET); + + /* Exit freeze mode */ + + imxrt_setfreeze(priv->base, 0); + if (!imxrt_waitfreezeack_change(priv->base, 0)) + { + ninfo("FLEXCAN: unfreeze fail\r\n"); + return -1; + } + + return 1; +} + +/**************************************************************************** + * Function: imxrt_reset + * + * Description: + * Put the EMAC in the non-operational, reset state + * + * Input Parameters: + * priv - Reference to the private FLEXCAN driver state structure + * + * Returned Value: + * None + * + * Assumptions: + * + ****************************************************************************/ + +static void imxrt_reset(struct imxrt_driver_s *priv) +{ + uint32_t regval; + uint32_t i; + + regval = getreg32(priv->base + IMXRT_CAN_MCR_OFFSET); + regval |= CAN_MCR_SOFTRST; + putreg32(regval, priv->base + IMXRT_CAN_MCR_OFFSET); + + if (!imxrt_waitmcr_change(priv->base, CAN_MCR_SOFTRST, 0)) + { + nerr("Reset failed"); + return; + } + + regval = getreg32(priv->base + IMXRT_CAN_MCR_OFFSET); + regval &= ~(CAN_MCR_SUPV); + putreg32(regval, priv->base + IMXRT_CAN_MCR_OFFSET); + + /* Initialize all MB rx and tx */ + + for (i = 0; i < TOTALMBCOUNT; i++) + { + ninfo("MB %i %p\r\n", i, &priv->rx[i]); + ninfo("MB %i %p\r\n", i, &priv->rx[i].id.w); + priv->rx[i].cs.cs = 0x0; + priv->rx[i].id.w = 0x0; + priv->rx[i].data[0].w00 = 0x0; + priv->rx[i].data[1].w00 = 0x0; + } + + regval = getreg32(priv->base + IMXRT_CAN_MCR_OFFSET); + regval |= CAN_MCR_SLFWAK | CAN_MCR_WRNEN | CAN_MCR_SRXDIS | + CAN_MCR_IRMQ | CAN_MCR_AEN | + (((TOTALMBCOUNT - 1) << CAN_MCR_MAXMB_SHIFT) & + CAN_MCR_MAXMB_MASK); + putreg32(regval, priv->base + IMXRT_CAN_MCR_OFFSET); + + regval = CAN_CTRL2_RRS | CAN_CTRL2_EACEN; + putreg32(regval, priv->base + IMXRT_CAN_CTRL2_OFFSET); + + for (i = 0; i < TOTALMBCOUNT; i++) + { + putreg32(0, priv->base + IMXRT_CAN_RXIMR_OFFSET(i)); + } + + /* Filtering catchall */ + + putreg32(0x3fffffff, priv->base + IMXRT_CAN_RX14MASK_OFFSET); + putreg32(0x3fffffff, priv->base + IMXRT_CAN_RX15MASK_OFFSET); + putreg32(0x3fffffff, priv->base + IMXRT_CAN_RXMGMASK_OFFSET); + putreg32(0x0, priv->base + IMXRT_CAN_RXFGMASK_OFFSET); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: imxrt_caninitialize + * + * Description: + * Initialize the CAN controller and driver + * + * Input Parameters: + * intf - In the case where there are multiple CAN, this value + * identifies which CAN is to be initialized. + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +int imxrt_caninitialize(int intf) +{ + struct imxrt_driver_s *priv; + int ret; +#ifdef TX_TIMEOUT_WQ + uint32_t i; +#endif + + switch (intf) + { +#ifdef CONFIG_IMXRT_FLEXCAN1 + case 1: + imxrt_clockall_can1(); + imxrt_clockall_can1_serial(); + priv = &g_flexcan1; + memset(priv, 0, sizeof(struct imxrt_driver_s)); + priv->base = IMXRT_CAN1_BASE; + priv->config = &imxrt_flexcan1_config; + + /* Default bitrate configuration */ + +# ifdef CONFIG_NET_CAN_CANFD + priv->arbi_timing.bitrate = CONFIG_FLEXCAN1_ARBI_BITRATE; + priv->arbi_timing.samplep = CONFIG_FLEXCAN1_ARBI_SAMPLEP; + priv->data_timing.bitrate = CONFIG_FLEXCAN1_DATA_BITRATE; + priv->data_timing.samplep = CONFIG_FLEXCAN1_DATA_SAMPLEP; +# else + priv->arbi_timing.bitrate = CONFIG_FLEXCAN1_BITRATE; + priv->arbi_timing.samplep = CONFIG_FLEXCAN1_SAMPLEP; +# endif + break; +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN2 + case 2: + imxrt_clockall_can2(); + imxrt_clockall_can2_serial(); + priv = &g_flexcan2; + memset(priv, 0, sizeof(struct imxrt_driver_s)); + priv->base = IMXRT_CAN2_BASE; + priv->config = &imxrt_flexcan2_config; + + /* Default bitrate configuration */ + +# ifdef CONFIG_NET_CAN_CANFD + priv->arbi_timing.bitrate = CONFIG_FLEXCAN2_ARBI_BITRATE; + priv->arbi_timing.samplep = CONFIG_FLEXCAN2_ARBI_SAMPLEP; + priv->data_timing.bitrate = CONFIG_FLEXCAN2_DATA_BITRATE; + priv->data_timing.samplep = CONFIG_FLEXCAN2_DATA_SAMPLEP; +# else + priv->arbi_timing.bitrate = CONFIG_FLEXCAN2_BITRATE; + priv->arbi_timing.samplep = CONFIG_FLEXCAN2_SAMPLEP; +# endif + break; +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN3 + case 3: + imxrt_clockall_can3(); + imxrt_clockall_can3_serial(); + priv = &g_flexcan3; + memset(priv, 0, sizeof(struct imxrt_driver_s)); + priv->base = IMXRT_CAN3_BASE; + priv->config = &imxrt_flexcan3_config; + + /* Default bitrate configuration */ + +# ifdef CONFIG_NET_CAN_CANFD + priv->arbi_timing.bitrate = CONFIG_FLEXCAN3_ARBI_BITRATE; + priv->arbi_timing.samplep = CONFIG_FLEXCAN3_ARBI_SAMPLEP; + priv->data_timing.bitrate = CONFIG_FLEXCAN3_DATA_BITRATE; + priv->data_timing.samplep = CONFIG_FLEXCAN3_DATA_SAMPLEP; +# else + priv->arbi_timing.bitrate = CONFIG_FLEXCAN3_BITRATE; + priv->arbi_timing.samplep = CONFIG_FLEXCAN3_SAMPLEP; +# endif + break; +#endif + + default: + return -ENODEV; + } + + if (!imxrt_bitratetotimeseg(&priv->arbi_timing, 1, 0)) + { + nerr("ERROR: Invalid CAN timings please try another sample point " + "or refer to the reference manual\n"); + return -1; + } + +#ifdef CONFIG_NET_CAN_CANFD + if (!imxrt_bitratetotimeseg(&priv->data_timing, 1, 1)) + { + nerr("ERROR: Invalid CAN data phase timings please try another " + "sample point or refer to the reference manual\n"); + return -1; + } +#endif + + imxrt_config_gpio(priv->config->tx_pin); + imxrt_config_gpio(priv->config->rx_pin); + + if (irq_attach(priv->config->irq, imxrt_flexcan_interrupt, priv)) + { + /* We could not attach the ISR to the interrupt */ + + nerr("ERROR: Failed to attach CAN bus IRQ\n"); + return -EAGAIN; + } + + /* Initialize the driver structure */ + + priv->dev.d_ifup = imxrt_ifup; /* I/F up (new IP address) callback */ + priv->dev.d_ifdown = imxrt_ifdown; /* I/F down callback */ + priv->dev.d_txavail = imxrt_txavail; /* New TX data callback */ +#ifdef CONFIG_NETDEV_IOCTL + priv->dev.d_ioctl = imxrt_ioctl; /* Support CAN ioctl() calls */ +#endif + priv->dev.d_private = (void *)priv; /* Used to recover private state from dev */ + +#ifdef TX_TIMEOUT_WQ + for (i = 0; i < TXMBCOUNT; i++) + { + priv->txtimeout[i] = wd_create(); /* Create TX timeout timer */ + } + +#endif + priv->rx = (struct mb_s *)(priv->base + IMXRT_CAN_MB_OFFSET); + priv->tx = (struct mb_s *)(priv->base + IMXRT_CAN_MB_OFFSET + + (sizeof(struct mb_s) * RXMBCOUNT)); + + /* Put the interface in the down state. This usually amounts to resetting + * the device and/or calling imxrt_ifdown(). + */ + + ninfo("callbacks done\r\n"); + + imxrt_ifdown(&priv->dev); + + /* Register the device with the OS so that socket IOCTLs can be performed */ + + netdev_register(&priv->dev, NET_LL_CAN); + + UNUSED(ret); + return OK; +} + +/**************************************************************************** + * Name: arm_caninitialize + * + * Description: + * Initialize the first network interface. If there are more than one + * interface in the chip, then board-specific logic will have to provide + * this function to determine which, if any, Ethernet controllers should + * be initialized. + * + ****************************************************************************/ + +#if !defined(CONFIG_NETDEV_LATEINIT) +void arm_netinitialize(void) +{ +#ifdef CONFIG_IMXRT_FLEXCAN1 + imxrt_caninitialize(1); +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN2 + imxrt_caninitialize(2); +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN3 + imxrt_caninitialize(3); +#endif +} +#endif + +#endif /* CONFIG_IMXRT_FLEXCAN */ diff --git a/arch/arm/src/imxrt/imxrt_flexcan.h b/arch/arm/src/imxrt/imxrt_flexcan.h new file mode 100644 index 0000000000000..e9cc2df9b953a --- /dev/null +++ b/arch/arm/src/imxrt/imxrt_flexcan.h @@ -0,0 +1,107 @@ +/**************************************************************************** + * arch/arm/src/imxrt/imxrt_flexcan.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_IMXRT_IMXRT_FLEXCAN_H +#define __ARCH_ARM_SRC_IMXRT_IMXRT_FLEXCAN_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include "hardware/imxrt_flexcan.h" + +#ifdef CONFIG_IMXRT_FLEXCAN + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Function: arm_caninitialize + * + * Description: + * Initialize the enabled CAN device interfaces. If there are more + * different network devices in the chip, then board-specific logic will + * have to provide this function to determine which, if any, network + * devices should be initialized. + * + * Input Parameters: + * None + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * Called very early in the initialization sequence. + * + ****************************************************************************/ + +#if !defined(CONFIG_NETDEV_LATEINIT) + +void arm_netinitialize(void); + +/**************************************************************************** + * Function: imxrt_caninitialize + * + * Description: + * Initialize the CAN controller and driver + * + * Input Parameters: + * intf - In the case where there are multiple CAN devices, this value + * identifies which CAN device is to be initialized. + * + * Returned Value: + * OK on success; Negated errno on failure. + * + * Assumptions: + * + ****************************************************************************/ + +#else + +int imxrt_caninitialize(int intf); + +#endif + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* CONFIG_IMXRT_FLEXCAN */ +#endif /* __ARCH_ARM_SRC_IMXRT_IMXRT_FLEXCAN_H */ \ No newline at end of file diff --git a/arch/arm/src/imxrt/imxrt_periphclks.h b/arch/arm/src/imxrt/imxrt_periphclks.h index bde77d5bc14bb..ad4d75804e9cd 100644 --- a/arch/arm/src/imxrt/imxrt_periphclks.h +++ b/arch/arm/src/imxrt/imxrt_periphclks.h @@ -1,4 +1,4 @@ -/******************************************************************************************** +/************************************************************************************ * arch/arm/src/imxrt/imxrt_periphclks.h * * Copyright (C) 2018 Gregory Nutt. All rights reserved. @@ -31,22 +31,22 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - *********************************************************************************************/ + ************************************************************************************/ #ifndef __ARCH_ARM_SRC_IMXRT_IMXRT_PERIPHCLKS_H #define __ARCH_ARM_SRC_IMXRT_IMXRT_PERIPHCLKS_H -/******************************************************************************************** +/************************************************************************************ * Included Files - *********************************************************************************************/ + ************************************************************************************/ #include #include #include "hardware/imxrt_ccm.h" -/******************************************************************************************** +/************************************************************************************ * Pre-processor Definitions - *********************************************************************************************/ + ************************************************************************************/ /* Clock is off during all modes. Stop enter hardware handshake is disabled. */ @@ -68,6 +68,8 @@ #define imxrt_clockoff_can1_serial() imxrt_periphclk_configure(CCM_CCGR_CAN1_SERIAL, CCM_CG_OFF) #define imxrt_clockoff_can2() imxrt_periphclk_configure(CCM_CCGR_CAN2, CCM_CG_OFF) #define imxrt_clockoff_can2_serial() imxrt_periphclk_configure(CCM_CCGR_CAN2_SERIAL, CCM_CG_OFF) +#define imxrt_clockoff_can3() imxrt_periphclk_configure(CCM_CCGR_CAN3, CCM_CG_OFF) +#define imxrt_clockoff_can3_serial() imxrt_periphclk_configure(CCM_CCGR_CAN3_SERIAL, CCM_CG_OFF) #define imxrt_clockoff_csi() imxrt_periphclk_configure(CCM_CCGR_CSI, CCM_CG_OFF) #define imxrt_clockoff_csu() imxrt_periphclk_configure(CCM_CCGR_CSU, CCM_CG_OFF) #define imxrt_clockoff_dcdc() imxrt_periphclk_configure(CCM_CCGR_DCDC, CCM_CG_OFF) @@ -177,6 +179,8 @@ #define imxrt_clockrun_can1_serial() imxrt_periphclk_configure(CCM_CCGR_CAN1_SERIAL, CCM_CG_RUN) #define imxrt_clockrun_can2() imxrt_periphclk_configure(CCM_CCGR_CAN2, CCM_CG_RUN) #define imxrt_clockrun_can2_serial() imxrt_periphclk_configure(CCM_CCGR_CAN2_SERIAL, CCM_CG_RUN) +#define imxrt_clockrun_can3() imxrt_periphclk_configure(CCM_CCGR_CAN3, CCM_CG_RUN) +#define imxrt_clockrun_can3_serial() imxrt_periphclk_configure(CCM_CCGR_CAN3_SERIAL, CCM_CG_RUN) #define imxrt_clockrun_csi() imxrt_periphclk_configure(CCM_CCGR_CSI, CCM_CG_RUN) #define imxrt_clockrun_csu() imxrt_periphclk_configure(CCM_CCGR_CSU, CCM_CG_RUN) #define imxrt_clockrun_dcdc() imxrt_periphclk_configure(CCM_CCGR_DCDC, CCM_CG_RUN) @@ -286,6 +290,8 @@ #define imxrt_clockall_can1_serial() imxrt_periphclk_configure(CCM_CCGR_CAN1_SERIAL, CCM_CG_ALL) #define imxrt_clockall_can2() imxrt_periphclk_configure(CCM_CCGR_CAN2, CCM_CG_ALL) #define imxrt_clockall_can2_serial() imxrt_periphclk_configure(CCM_CCGR_CAN2_SERIAL, CCM_CG_ALL) +#define imxrt_clockall_can3() imxrt_periphclk_configure(CCM_CCGR_CAN3, CCM_CG_ALL) +#define imxrt_clockall_can3_serial() imxrt_periphclk_configure(CCM_CCGR_CAN3_SERIAL, CCM_CG_ALL) #define imxrt_clockall_csi() imxrt_periphclk_configure(CCM_CCGR_CSI, CCM_CG_ALL) #define imxrt_clockall_csu() imxrt_periphclk_configure(CCM_CCGR_CSU, CCM_CG_ALL) #define imxrt_clockall_dcdc() imxrt_periphclk_configure(CCM_CCGR_DCDC, CCM_CG_ALL) @@ -384,11 +390,7 @@ extern "C" #define EXTERN extern #endif -/******************************************************************************************** - * Public Functions - *********************************************************************************************/ - -/******************************************************************************************** +/************************************************************************************ * Name: imxrt_periphclk_configure * * Description: @@ -403,7 +405,7 @@ extern "C" * Returned Value: * None * - *********************************************************************************************/ + ************************************************************************************/ void imxrt_periphclk_configure(uintptr_t regaddr, unsigned int index, unsigned int value); diff --git a/boards/arm/imxrt/imxrt1060-evk/README.txt b/boards/arm/imxrt/imxrt1060-evk/README.txt index c39f7d876510a..06ecda5820961 100644 --- a/boards/arm/imxrt/imxrt1060-evk/README.txt +++ b/boards/arm/imxrt/imxrt1060-evk/README.txt @@ -184,6 +184,31 @@ Configurations Configuration sub-directories ----------------------------- + can: + + This is an nsh configuration (see below) with added support of CAN driver. + FlexCAN3 is chosen as default, the change can be made at System type peripheral + selection. Please note that only FlexCAN3 and FlexCAN2 is available on this board. + + Bitrate and sample point can be also changed at System type peripheral selection, + basic values are 1 MHz for bitrate and 0.80 for sample point. The FlexCAN driver + for imxrt runs at 80 MHz clock frequency. + + The configuration also includes CAN utilities as candump and cansend. + + canfd: + + This is an nsh configuration (see below) with added support of CAN_FD driver. + FlexCAN3 is chosen as default, please note that only FlexCAN3 is capable of + providing CAN_FD support. + + Bitrate and sample point can be also changed at System type peripheral selection, + basic values are 1 MHz for bitrate and 0.80 for sample point for arbitration phase + and 4 MHz (bitrate) and 0.90 (sample point) for data phase. The FlexCAN driver + for imxrt runs at 80 MHz clock frequency. + + The configuration also includes CAN utilities as candump and cansend. + knsh: This is identical to the nsh configuration below except that NuttX diff --git a/boards/arm/imxrt/imxrt1060-evk/configs/can/defconfig b/boards/arm/imxrt/imxrt1060-evk/configs/can/defconfig new file mode 100644 index 0000000000000..eb1ffce4b2e7d --- /dev/null +++ b/boards/arm/imxrt/imxrt1060-evk/configs/can/defconfig @@ -0,0 +1,79 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_NET_CAN_CANFD is not set +# CONFIG_NET_ETHERNET is not set +# CONFIG_NET_IPv4 is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="imxrt1060-evk" +CONFIG_ARCH_BOARD_IMXRT1060_EVK=y +CONFIG_ARCH_CHIP="imxrt" +CONFIG_ARCH_CHIP_IMXRT=y +CONFIG_ARCH_CHIP_MIMXRT1062DVL6A=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARD_LOOPSPERMSEC=104926 +CONFIG_BUILTIN=y +CONFIG_CAN=y +CONFIG_CANUTILS_CANDUMP=y +CONFIG_CANUTILS_CANSEND=y +CONFIG_DEBUG_BINFMT=y +CONFIG_DEBUG_BINFMT_ERROR=y +CONFIG_DEBUG_BINFMT_INFO=y +CONFIG_DEBUG_BINFMT_WARN=y +CONFIG_DEBUG_CAN=y +CONFIG_DEBUG_CAN_ERROR=y +CONFIG_DEBUG_CAN_INFO=y +CONFIG_DEBUG_CAN_WARN=y +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_FEATURES=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_INFO=y +CONFIG_DEBUG_IRQ=y +CONFIG_DEBUG_IRQ_ERROR=y +CONFIG_DEBUG_IRQ_INFO=y +CONFIG_DEBUG_IRQ_WARN=y +CONFIG_DEBUG_NET=y +CONFIG_DEBUG_NET_ERROR=y +CONFIG_DEBUG_NET_INFO=y +CONFIG_DEBUG_NET_WARN=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_WARN=y +CONFIG_FS_PROCFS=y +CONFIG_IDLETHREAD_STACKSIZE=2048 +CONFIG_IMXRT_FLEXCAN3=y +CONFIG_IMXRT_LPUART1=y +CONFIG_INTELHEX_BINARY=y +CONFIG_LPUART1_SERIAL_CONSOLE=y +CONFIG_MAX_TASKS=16 +CONFIG_NET=y +CONFIG_NETDEVICES=y +CONFIG_NETDEV_IFINDEX=y +CONFIG_NETDEV_LATEINIT=y +CONFIG_NETDEV_STATISTICS=y +CONFIG_NET_CAN=y +CONFIG_NET_CAN_NOTIFIER=y +CONFIG_NET_SOCKOPTS=y +CONFIG_NET_STATISTICS=y +CONFIG_NET_TIMESTAMP=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_RAM_SIZE=1048576 +CONFIG_RAM_START=0x20200000 +CONFIG_SCHED_HPWORK=y +CONFIG_SIG_DEFAULT=y +CONFIG_START_DAY=14 +CONFIG_START_MONTH=3 +CONFIG_SYSTEM_NSH=y +CONFIG_USER_ENTRYPOINT="nsh_main" diff --git a/boards/arm/imxrt/imxrt1060-evk/configs/canfd/defconfig b/boards/arm/imxrt/imxrt1060-evk/configs/canfd/defconfig new file mode 100644 index 0000000000000..5c80b3393a431 --- /dev/null +++ b/boards/arm/imxrt/imxrt1060-evk/configs/canfd/defconfig @@ -0,0 +1,80 @@ +# +# This file is autogenerated: PLEASE DO NOT EDIT IT. +# +# You can use "make menuconfig" to make any modifications to the installed .config file. +# You can then do "make savedefconfig" to generate a new defconfig file that includes your +# modifications. +# +# CONFIG_NET_ETHERNET is not set +# CONFIG_NET_IPv4 is not set +CONFIG_ARCH="arm" +CONFIG_ARCH_BOARD="imxrt1060-evk" +CONFIG_ARCH_BOARD_IMXRT1060_EVK=y +CONFIG_ARCH_CHIP="imxrt" +CONFIG_ARCH_CHIP_IMXRT=y +CONFIG_ARCH_CHIP_MIMXRT1062DVL6A=y +CONFIG_ARCH_STACKDUMP=y +CONFIG_ARMV7M_DCACHE=y +CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y +CONFIG_ARMV7M_ICACHE=y +CONFIG_ARMV7M_USEBASEPRI=y +CONFIG_BOARD_LOOPSPERMSEC=104926 +CONFIG_BUILTIN=y +CONFIG_CAN=y +CONFIG_CANUTILS_CANDUMP=y +CONFIG_CANUTILS_CANSEND=y +CONFIG_CAN_EXTID=y +CONFIG_CAN_FD=y +CONFIG_DEBUG_BINFMT=y +CONFIG_DEBUG_BINFMT_ERROR=y +CONFIG_DEBUG_BINFMT_INFO=y +CONFIG_DEBUG_BINFMT_WARN=y +CONFIG_DEBUG_CAN=y +CONFIG_DEBUG_CAN_ERROR=y +CONFIG_DEBUG_CAN_INFO=y +CONFIG_DEBUG_CAN_WARN=y +CONFIG_DEBUG_ERROR=y +CONFIG_DEBUG_FEATURES=y +CONFIG_DEBUG_FULLOPT=y +CONFIG_DEBUG_INFO=y +CONFIG_DEBUG_IRQ=y +CONFIG_DEBUG_IRQ_ERROR=y +CONFIG_DEBUG_IRQ_INFO=y +CONFIG_DEBUG_IRQ_WARN=y +CONFIG_DEBUG_NET=y +CONFIG_DEBUG_NET_ERROR=y +CONFIG_DEBUG_NET_INFO=y +CONFIG_DEBUG_NET_WARN=y +CONFIG_DEBUG_SYMBOLS=y +CONFIG_DEBUG_WARN=y +CONFIG_FS_PROCFS=y +CONFIG_IDLETHREAD_STACKSIZE=2048 +CONFIG_IMXRT_FLEXCAN3=y +CONFIG_IMXRT_LPUART1=y +CONFIG_INTELHEX_BINARY=y +CONFIG_LPUART1_SERIAL_CONSOLE=y +CONFIG_MAX_TASKS=16 +CONFIG_NET=y +CONFIG_NETDEVICES=y +CONFIG_NETDEV_IFINDEX=y +CONFIG_NETDEV_LATEINIT=y +CONFIG_NETDEV_STATISTICS=y +CONFIG_NET_CAN=y +CONFIG_NET_CAN_NOTIFIER=y +CONFIG_NET_CAN_SOCK_OPTS=y +CONFIG_NET_STATISTICS=y +CONFIG_NET_TIMESTAMP=y +CONFIG_NFILE_DESCRIPTORS=8 +CONFIG_NSH_ARCHINIT=y +CONFIG_NSH_BUILTIN_APPS=y +CONFIG_NSH_FILEIOSIZE=512 +CONFIG_NSH_LINELEN=64 +CONFIG_NSH_READLINE=y +CONFIG_RAM_SIZE=1048576 +CONFIG_RAM_START=0x20200000 +CONFIG_SCHED_HPWORK=y +CONFIG_SIG_DEFAULT=y +CONFIG_START_DAY=14 +CONFIG_START_MONTH=3 +CONFIG_SYSTEM_NSH=y +CONFIG_USER_ENTRYPOINT="nsh_main" diff --git a/boards/arm/imxrt/imxrt1060-evk/include/board.h b/boards/arm/imxrt/imxrt1060-evk/include/board.h index d83a9e47b819b..20cc18df1c120 100644 --- a/boards/arm/imxrt/imxrt1060-evk/include/board.h +++ b/boards/arm/imxrt/imxrt1060-evk/include/board.h @@ -126,6 +126,9 @@ #define IMXRT_LPI2C_CLK_SELECT CCM_CSCDR2_LPI2C_CLK_SEL_PLL3_60M #define IMXRT_LSI2C_PODF_DIVIDER 5 +#define IMXRT_CAN_CLK_SELECT CCM_CSCMR2_CAN_CLK_SEL_PLL3_SW_80 +#define IMXRT_CAN_PODF_DIVIDER 1 + #define IMXRT_SYS_PLL_SELECT CCM_ANALOG_PLL_SYS_DIV_SELECT_22 #define IMXRT_USB1_PLL_DIV_SELECT CCM_ANALOG_PLL_USB1_DIV_SELECT_20 @@ -323,6 +326,14 @@ #define GPIO_LPSPI3_MISO (GPIO_LPSPI3_SDI_2|IOMUX_LPSPI_DEFAULT) /* GPIO_AD_B0_02 */ #define GPIO_LPSPI3_MOSI (GPIO_LPSPI3_SDO_2|IOMUX_LPSPI_DEFAULT) /* GPIO_AD_B0_01 */ +/* FlexCAN */ + +#define GPIO_FLEXCAN2_TX (GPIO_FLEXCAN2_TX_3|IOMUX_CAN_DEFAULT) +#define GPIO_FLEXCAN2_RX (GPIO_FLEXCAN2_RX_3|IOMUX_CAN_DEFAULT) + +#define GPIO_FLEXCAN3_TX (GPIO_FLEXCAN3_TX_2|IOMUX_CAN_DEFAULT) +#define GPIO_FLEXCAN3_RX (GPIO_FLEXCAN3_RX_2|IOMUX_CAN_DEFAULT) + /**************************************************************************** * Public Types ****************************************************************************/ diff --git a/boards/arm/imxrt/imxrt1060-evk/src/Makefile b/boards/arm/imxrt/imxrt1060-evk/src/Makefile index 9efc123ea2dc0..c17981ae1d161 100644 --- a/boards/arm/imxrt/imxrt1060-evk/src/Makefile +++ b/boards/arm/imxrt/imxrt1060-evk/src/Makefile @@ -89,4 +89,8 @@ ifeq ($(CONFIG_IMXRT_USBOTG),y) CSRCS += imxrt_usbhost.c endif +ifeq ($(CONFIG_IMXRT_FLEXCAN),y) +CSRCS += imxrt_flexcan.c +endif + include $(TOPDIR)/boards/Board.mk diff --git a/boards/arm/imxrt/imxrt1060-evk/src/imxrt1060-evk.h b/boards/arm/imxrt/imxrt1060-evk/src/imxrt1060-evk.h index 216b916d6fbaf..b76dc0872991a 100644 --- a/boards/arm/imxrt/imxrt1060-evk/src/imxrt1060-evk.h +++ b/boards/arm/imxrt/imxrt1060-evk/src/imxrt1060-evk.h @@ -88,6 +88,8 @@ #define GPIO_LED (GPIO_OUTPUT | IOMUX_LED_DEFAULT | \ GPIO_OUTPUT_ZERO | GPIO_PORT1 | GPIO_PIN9) /* AD_BO_09 */ +#define LED_DRIVER_PATH "/dev/userleds" + /* Buttons ******************************************************************/ /* The IMXRT board has one external user button @@ -275,6 +277,18 @@ void imxrt_autoled_initialize(void); int imxrt_gpio_initialize(void); #endif +/**************************************************************************** + * Name: imxrt_can_setup + * + * Description: + * Initialize CAN and register the CAN device + * + ****************************************************************************/ + +#ifdef CONFIG_IMXRT_FLEXCAN +int imxrt_can_setup(void); +#endif + /**************************************************************************** * Name: imxrt_adc_initialize * diff --git a/boards/arm/imxrt/imxrt1060-evk/src/imxrt_appinit.c b/boards/arm/imxrt/imxrt1060-evk/src/imxrt_appinit.c index aa4a70165f2dc..994cc9c2067f7 100644 --- a/boards/arm/imxrt/imxrt1060-evk/src/imxrt_appinit.c +++ b/boards/arm/imxrt/imxrt1060-evk/src/imxrt_appinit.c @@ -39,13 +39,17 @@ ****************************************************************************/ #include - +#include #include #include #include "imxrt1060-evk.h" +#if !defined(CONFIG_ARCH_LEDS) && defined(CONFIG_USERLED_LOWER) +# define HAVE_LEDS 0 +#endif + #ifdef CONFIG_LIB_BOARDCTL /**************************************************************************** @@ -79,6 +83,18 @@ int board_app_initialize(uintptr_t arg) { +#ifdef HAVE_LEDS + /* Register the LED driver */ + + int ret; + ret = userled_lower_initialize(LED_DRIVER_PATH); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: userled_lower_initialize() failed: %d\n", ret); + return ret; + } +#endif + #ifndef CONFIG_BOARD_LATE_INITIALIZE /* Perform board initialization */ diff --git a/boards/arm/imxrt/imxrt1060-evk/src/imxrt_bringup.c b/boards/arm/imxrt/imxrt1060-evk/src/imxrt_bringup.c index c0e07ba79d486..e9c0c774a0607 100644 --- a/boards/arm/imxrt/imxrt1060-evk/src/imxrt_bringup.c +++ b/boards/arm/imxrt/imxrt1060-evk/src/imxrt_bringup.c @@ -63,6 +63,7 @@ # include #endif +#include "imxrt_enet.h" #include "imxrt1060-evk.h" #include /* Must always be included last */ @@ -212,6 +213,19 @@ int imxrt_bringup(void) } #endif +#if defined(CONFIG_IMXRT_ENET) && defined(CONFIG_NETDEV_LATEINIT) + ret = imxrt_netinitialize(0); +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN + ret = imxrt_can_setup(); + if (ret < 0) + { + syslog(LOG_ERR, "ERROR: imxrt_can_setup() failed: %d\n", ret); + return ret; + } +#endif + #ifdef CONFIG_DEV_GPIO /* Initialize the GPIO driver */ diff --git a/boards/arm/imxrt/imxrt1060-evk/src/imxrt_flexcan.c b/boards/arm/imxrt/imxrt1060-evk/src/imxrt_flexcan.c new file mode 100644 index 0000000000000..f71ccb9bf7325 --- /dev/null +++ b/boards/arm/imxrt/imxrt1060-evk/src/imxrt_flexcan.c @@ -0,0 +1,83 @@ +/**************************************************************************** + * boards/arm/imxrt/imxrt1060-evk/src/imxrt_flexcan.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "imxrt_flexcan.h" +#include "imxrt1060-evk.h" + +#ifdef CONFIG_IMXRT_FLEXCAN + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: imxrt_can_setup + * + * Description: + * Initialize CAN and register the CAN device + * + ****************************************************************************/ + +int imxrt_can_setup(void) +{ + int ret; +#if defined(CONFIG_IMXRT_FLEXCAN3) && defined(CONFIG_IMXRT_FLEXCAN2) + canerr("ERROR: Only one FlexCAN can be defined at the same time\n"); + return -ENODEV; +#endif + +#ifdef CONFIG_IMXRT_FLEXCAN3 + /* Call arm_caninitialize() to get an instance of the CAN interface */ + + ret = imxrt_caninitialize(3); + if (ret < 0) + { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } +#elif CONFIG_IMXRT_FLEXCAN2 + ret = imxrt_caninitialize(2); + if (ret < 0) + { + canerr("ERROR: Failed to get CAN interface\n"); + return -ENODEV; + } +#elif CONFIG_IMXRT_FLEXCAN1 + canerr("ERROR: FlexCAN1 is not available on imxrt1060-evk\n"); + return -ENODEV; +#else + return -ENODEV; +#endif + return OK; +} + +#endif /* CONFIG_IMXRT_FLEXCAN */