Browse Source

drivers: can: mcp251xfd: Add driver

This continue PR #31270. The updated changes are:
- Updated to work with latest zephyr
- Inplace reads/writes of registers
- Batch read of RX messages when multiple messages can be read
- FIFO abstraction of RX/TEF queues
- Handle ivmif errors
- Use READ_CRC for register reads
- Use bitmasks instead of bitfield members
- Rename mcp25xxfd to mcp251xfd
- General cleanups

Signed-off-by: Andriy Gelman <andriy.gelman@gmail.com>
pull/63348/head
Andriy Gelman 2 years ago committed by Johan Hedberg
parent
commit
31bef35897
  1. 2
      drivers/can/CMakeLists.txt
  2. 2
      drivers/can/Kconfig
  3. 61
      drivers/can/Kconfig.mcp251xfd
  4. 56
      drivers/can/Kconfig.mcp25xxfd
  5. 1786
      drivers/can/can_mcp251xfd.c
  6. 557
      drivers/can/can_mcp251xfd.h
  7. 1088
      drivers/can/can_mcp25xxfd.c
  8. 537
      drivers/can/can_mcp25xxfd.h
  9. 80
      dts/bindings/can/microchip,mcp251xfd.yaml
  10. 40
      dts/bindings/can/microchip,mcp25xxfd.yaml

2
drivers/can/CMakeLists.txt

@ -10,7 +10,7 @@ zephyr_library_sources_ifdef(CONFIG_CAN_FAKE can_fake.c) @@ -10,7 +10,7 @@ zephyr_library_sources_ifdef(CONFIG_CAN_FAKE can_fake.c)
zephyr_library_sources_ifdef(CONFIG_CAN_LOOPBACK can_loopback.c)
zephyr_library_sources_ifdef(CONFIG_CAN_MCAN can_mcan.c)
zephyr_library_sources_ifdef(CONFIG_CAN_MCP2515 can_mcp2515.c)
zephyr_library_sources_ifdef(CONFIG_CAN_MCP25XXFD can_mcp25xxfd.c)
zephyr_library_sources_ifdef(CONFIG_CAN_MCP251XFD can_mcp251xfd.c)
zephyr_library_sources_ifdef(CONFIG_CAN_MCUX_FLEXCAN can_mcux_flexcan.c)
zephyr_library_sources_ifdef(CONFIG_CAN_SAM can_sam.c)
zephyr_library_sources_ifdef(CONFIG_CAN_SAM0 can_sam0.c)

2
drivers/can/Kconfig

@ -100,7 +100,7 @@ source "drivers/can/Kconfig.kvaser" @@ -100,7 +100,7 @@ source "drivers/can/Kconfig.kvaser"
source "drivers/can/Kconfig.fake"
source "drivers/can/Kconfig.nxp_s32"
source "drivers/can/Kconfig.tcan4x5x"
source "drivers/can/Kconfig.mcp25xxfd"
source "drivers/can/Kconfig.mcp251xfd"
source "drivers/can/transceiver/Kconfig"

61
drivers/can/Kconfig.mcp251xfd

@ -0,0 +1,61 @@ @@ -0,0 +1,61 @@
# MCP25XXFD CAN configuration options
# Copyright (c) 2020 Abram Early
# Copyright (c) 2023 Andriy Gelman
# SPDX-License-Identifier: Apache-2.0
config CAN_MCP251XFD
bool "MCP25XXFD CAN Driver"
default y
depends on DT_HAS_MICROCHIP_MCP251XFD_ENABLED
select CRC
select SPI
help
Enable MCP25XXFD CAN Driver
if CAN_MCP251XFD
config CAN_MCP251XFD_MAX_TX_QUEUE
int "Maximum number of queued messages"
default 8
range 1 32
help
Defines the array size of transmit callback pointers and semaphores,
as well as the number of messages in the TX queue.
config CAN_MCP251XFD_RX_FIFO_ITEMS
int "Number of CAN messages in the RX fifo"
default 16
range 1 32
help
Defines the number of CAN messages in the RX fifo.
config CAN_MCP251XFD_INT_THREAD_STACK_SIZE
int "Stack size for interrupt handler"
default 768
help
Size of the stack used for internal thread which is ran for
interrupt handling and incoming packets.
config CAN_MCP251XFD_INT_THREAD_PRIO
int "Priority for interrupt handler"
default 2
help
Thread priority of the interrupt handler. A higher number implies a
higher priority. The thread is cooperative and will not be interrupted by
another thread until execution is released.
config CAN_MCP251XFD_READ_CRC_RETRIES
int "Number of retries during SFR register read"
default 5
help
Number of retries during SFR register read if CRC fails.
config CAN_MAX_FILTER
int "Maximum number of concurrent active filters"
default 5
range 1 31
help
Maximum number of filters supported by the can_add_rx_callback() API call.
endif # CAN_MCP251XFD

56
drivers/can/Kconfig.mcp25xxfd

@ -1,56 +0,0 @@ @@ -1,56 +0,0 @@
# MCP25XXFD CAN configuration options
# Copyright (c) 2020 Abram Early
# SPDX-License-Identifier: Apache-2.0
DT_COMPAT_MICROCHIP_MCP25XXFD_CAN := microchip,mcp25xxfd
config CAN_MCP25XXFD
bool "MCP25XXFD CAN Driver"
default $(dt_compat_enabled,$(DT_COMPAT_MICROCHIP_MCP25XXFD_CAN))
depends on SPI
select CAN_AUTO_BUS_OFF_RECOVERY
select CAN_HAS_CANFD
select CAN_HAS_RX_TIMESTAMP
help
Enable MCP25XXFD CAN Driver
if CAN_MCP25XXFD
config CAN_MCP25XXFD_MAX_TX_QUEUE
int "Maximum number of queued messages"
default 4
range 1 31
help
Defines the array size of transmit callback pointers and semaphores,
as well as the number of TX FIFOs allocated on the MCP25XXFD.
config CAN_MCP25XXFD_INT_THREAD_STACK_SIZE
int "Stack size for interrupt handler"
default 768
help
Size of the stack used for internal thread which is ran for
interrupt handling and incoming packets.
config CAN_MCP25XXFD_INT_THREAD_PRIO
int "Priority for interrupt handler"
default 2
help
Priority level of the internal thread which is ran for
interrupt handling and incoming packets.
config CAN_MAX_FILTER
int "Maximum number of concurrent active filters"
default 5
range 1 31
help
Defines the array size of the callback/msgq pointers.
Must be at least the size of concurrent reads.
config CAN_MCP25XXFD_INIT_PRIORITY
int "Init priority"
default 80
help
MCP25XXFD driver initialization priority, must be higher than SPI.
endif # CAN_MCP25XXFD

1786
drivers/can/can_mcp251xfd.c

File diff suppressed because it is too large Load Diff

557
drivers/can/can_mcp251xfd.h

@ -0,0 +1,557 @@ @@ -0,0 +1,557 @@
/*
* Copyright (c) 2020 Abram Early
* Copyright (c) 2023 Andriy Gelman
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_CAN_MICROCHIP_MCP251XFD_H_
#define ZEPHYR_DRIVERS_CAN_MICROCHIP_MCP251XFD_H_
#include <stdint.h>
#include <zephyr/drivers/can.h>
#include <zephyr/drivers/gpio.h>
#include <zephyr/drivers/spi.h>
#define MCP251XFD_UINT32_FLAG_TO_BYTE_MASK(flag_u32) \
((flag_u32) >> ROUND_DOWN(LOG2((flag_u32)), 8))
#define MCP251XFD_RAM_START_ADDR 0x400
#define MCP251XFD_RAM_SIZE 2048
#define MCP251XFD_RAM_ALIGNMENT 4
#define MCP251XFD_PAYLOAD_SIZE CAN_MAX_DLEN
#define MCP251XFD_FIFO_TYPE_TEF 0
#define MCP251XFD_FIFO_TYPE_RX 1
#define MCP251XFD_TEF_FIFO_ITEM_SIZE 8
#define MCP251XFD_TX_QUEUE_ITEM_SIZE (8 + MCP251XFD_PAYLOAD_SIZE)
#if defined(CONFIG_CAN_RX_TIMESTAMP)
#define MCP251XFD_RX_FIFO_ITEM_SIZE (4 + 8 + MCP251XFD_PAYLOAD_SIZE)
#else
#define MCP251XFD_RX_FIFO_ITEM_SIZE (8 + MCP251XFD_PAYLOAD_SIZE)
#endif
#define MCP251XFD_TEF_FIFO_START_ADDR 0
#define MCP251XFD_TEF_FIFO_ITEMS CONFIG_CAN_MCP251XFD_MAX_TX_QUEUE
#define MCP251XFD_TEF_FIFO_SIZE (MCP251XFD_TEF_FIFO_ITEMS * MCP251XFD_TEF_FIFO_ITEM_SIZE)
#define MCP251XFD_TX_QUEUE_START_ADDR MCP251XFD_TEF_FIFO_SIZE
#define MCP251XFD_TX_QUEUE_ITEMS CONFIG_CAN_MCP251XFD_MAX_TX_QUEUE
#define MCP251XFD_TX_QUEUE_SIZE (MCP251XFD_TX_QUEUE_ITEMS * MCP251XFD_TX_QUEUE_ITEM_SIZE)
#define MCP251XFD_RX_FIFO_START_ADDR (MCP251XFD_TX_QUEUE_START_ADDR + MCP251XFD_TX_QUEUE_SIZE)
#define MCP251XFD_RX_FIFO_SIZE_MAX (MCP251XFD_RAM_SIZE - MCP251XFD_RX_FIFO_START_ADDR)
#define MCP251XFD_RX_FIFO_ITEMS_MAX (MCP251XFD_RX_FIFO_SIZE_MAX / MCP251XFD_RX_FIFO_ITEM_SIZE)
#define MCP251XFD_RX_FIFO_ITEMS CONFIG_CAN_MCP251XFD_RX_FIFO_ITEMS
#define MCP251XFD_RX_FIFO_SIZE (MCP251XFD_RX_FIFO_ITEMS * MCP251XFD_RX_FIFO_ITEM_SIZE)
#define MCP251XFD_RX_FIFO_IDX 1
#define MCP251XFD_REG_SIZE 4
#define MCP251XFD_CRC_POLY 0x8005
#define MCP251XFD_CRC_SEED 0xffff
BUILD_ASSERT(MCP251XFD_TEF_FIFO_SIZE + MCP251XFD_TX_QUEUE_SIZE +
MCP251XFD_RX_FIFO_SIZE <= MCP251XFD_RAM_SIZE,
"Cannot fit FIFOs into RAM");
/* Timeout for changing mode */
#define MCP251XFD_MODE_CHANGE_TIMEOUT_USEC 200000U
#define MCP251XFD_MODE_CHANGE_RETRIES 100
#define MCP251XFD_PLLRDY_TIMEOUT_USEC 100000
#define MCP251XFD_PLLRDY_RETRIES 100
#define MCP251XFD_MAX_INT_HANDLER_CALLS 10
#define MCP251XFD_INT_HANDLER_SLEEP_USEC 10000
struct mcp251xfd_mailbox {
can_tx_callback_t cb;
void *cb_arg;
};
#define MCP251XFD_SPI_CMD_LEN 2
#define MCP251XFD_SPI_LEN_FIELD_LEN 1
#define MCP251XFD_SPI_CRC_LEN 2
/* MPC251x registers - mostly copied from Linux kernel implementation of driver */
/* CAN FD Controller Module SFR */
#define MCP251XFD_REG_CON 0x00
#define MCP251XFD_REG_CON_TXBWS_MASK GENMASK(31, 28)
#define MCP251XFD_REG_CON_ABAT BIT(27)
#define MCP251XFD_REG_CON_REQOP_MASK GENMASK(26, 24)
#define MCP251XFD_REG_CON_MODE_MIXED 0
#define MCP251XFD_REG_CON_MODE_SLEEP 1
#define MCP251XFD_REG_CON_MODE_INT_LOOPBACK 2
#define MCP251XFD_REG_CON_MODE_LISTENONLY 3
#define MCP251XFD_REG_CON_MODE_CONFIG 4
#define MCP251XFD_REG_CON_MODE_EXT_LOOPBACK 5
#define MCP251XFD_REG_CON_MODE_CAN2_0 6
#define MCP251XFD_REG_CON_MODE_RESTRICTED 7
#define MCP251XFD_REG_CON_OPMOD_MASK GENMASK(23, 21)
#define MCP251XFD_REG_CON_TXQEN BIT(20)
#define MCP251XFD_REG_CON_STEF BIT(19)
#define MCP251XFD_REG_CON_SERR2LOM BIT(18)
#define MCP251XFD_REG_CON_ESIGM BIT(17)
#define MCP251XFD_REG_CON_RTXAT BIT(16)
#define MCP251XFD_REG_CON_BRSDIS BIT(12)
#define MCP251XFD_REG_CON_BUSY BIT(11)
#define MCP251XFD_REG_CON_WFT_MASK GENMASK(10, 9)
#define MCP251XFD_REG_CON_WFT_T00FILTER 0x0
#define MCP251XFD_REG_CON_WFT_T01FILTER 0x1
#define MCP251XFD_REG_CON_WFT_T10FILTER 0x2
#define MCP251XFD_REG_CON_WFT_T11FILTER 0x3
#define MCP251XFD_REG_CON_WAKFIL BIT(8)
#define MCP251XFD_REG_CON_PXEDIS BIT(6)
#define MCP251XFD_REG_CON_ISOCRCEN BIT(5)
#define MCP251XFD_REG_CON_DNCNT_MASK GENMASK(4, 0)
#define MCP251XFD_REG_CON_B2 (MCP251XFD_REG_CON + 2)
#define MCP251XFD_REG_CON_B3 (MCP251XFD_REG_CON + 3)
#define MCP251XFD_REG_NBTCFG 0x04
#define MCP251XFD_REG_NBTCFG_BRP_MASK GENMASK(31, 24)
#define MCP251XFD_REG_NBTCFG_TSEG1_MASK GENMASK(23, 16)
#define MCP251XFD_REG_NBTCFG_TSEG2_MASK GENMASK(14, 8)
#define MCP251XFD_REG_NBTCFG_SJW_MASK GENMASK(6, 0)
#define MCP251XFD_REG_DBTCFG 0x08
#define MCP251XFD_REG_DBTCFG_BRP_MASK GENMASK(31, 24)
#define MCP251XFD_REG_DBTCFG_TSEG1_MASK GENMASK(20, 16)
#define MCP251XFD_REG_DBTCFG_TSEG2_MASK GENMASK(11, 8)
#define MCP251XFD_REG_DBTCFG_SJW_MASK GENMASK(3, 0)
#define MCP251XFD_REG_TDC 0x0c
#define MCP251XFD_REG_TDC_EDGFLTEN BIT(25)
#define MCP251XFD_REG_TDC_SID11EN BIT(24)
#define MCP251XFD_REG_TDC_TDCMOD_MASK GENMASK(17, 16)
#define MCP251XFD_REG_TDC_TDCMOD_AUTO 2
#define MCP251XFD_REG_TDC_TDCMOD_MANUAL 1
#define MCP251XFD_REG_TDC_TDCMOD_DISABLED 0
#define MCP251XFD_REG_TDC_TDCO_MASK GENMASK(14, 8)
#define MCP251XFD_REG_TDC_TDCV_MASK GENMASK(5, 0)
#define MCP251XFD_REG_TDC_TDCO_MIN -64
#define MCP251XFD_REG_TDC_TDCO_MAX 63
#define MCP251XFD_REG_TBC 0x10
#define MCP251XFD_REG_TSCON 0x14
#define MCP251XFD_REG_TSCON_TSRES BIT(18)
#define MCP251XFD_REG_TSCON_TSEOF BIT(17)
#define MCP251XFD_REG_TSCON_TBCEN BIT(16)
#define MCP251XFD_REG_TSCON_TBCPRE_MASK GENMASK(9, 0)
#define MCP251XFD_REG_VEC 0x18
#define MCP251XFD_REG_VEC_RXCODE_MASK GENMASK(30, 24)
#define MCP251XFD_REG_VEC_TXCODE_MASK GENMASK(22, 16)
#define MCP251XFD_REG_VEC_FILHIT_MASK GENMASK(12, 8)
#define MCP251XFD_REG_VEC_ICODE_MASK GENMASK(6, 0)
#define MCP251XFD_REG_INT 0x1c
#define MCP251XFD_REG_INT_IF_MASK GENMASK(15, 0)
#define MCP251XFD_REG_INT_IE_MASK GENMASK(31, 16)
#define MCP251XFD_REG_INT_IVMIE BIT(31)
#define MCP251XFD_REG_INT_WAKIE BIT(30)
#define MCP251XFD_REG_INT_CERRIE BIT(29)
#define MCP251XFD_REG_INT_SERRIE BIT(28)
#define MCP251XFD_REG_INT_RXOVIE BIT(27)
#define MCP251XFD_REG_INT_TXATIE BIT(26)
#define MCP251XFD_REG_INT_SPICRCIE BIT(25)
#define MCP251XFD_REG_INT_ECCIE BIT(24)
#define MCP251XFD_REG_INT_TEFIE BIT(20)
#define MCP251XFD_REG_INT_MODIE BIT(19)
#define MCP251XFD_REG_INT_TBCIE BIT(18)
#define MCP251XFD_REG_INT_RXIE BIT(17)
#define MCP251XFD_REG_INT_TXIE BIT(16)
#define MCP251XFD_REG_INT_IVMIF BIT(15)
#define MCP251XFD_REG_INT_WAKIF BIT(14)
#define MCP251XFD_REG_INT_CERRIF BIT(13)
#define MCP251XFD_REG_INT_SERRIF BIT(12)
#define MCP251XFD_REG_INT_RXOVIF BIT(11)
#define MCP251XFD_REG_INT_TXATIF BIT(10)
#define MCP251XFD_REG_INT_SPICRCIF BIT(9)
#define MCP251XFD_REG_INT_ECCIF BIT(8)
#define MCP251XFD_REG_INT_TEFIF BIT(4)
#define MCP251XFD_REG_INT_MODIF BIT(3)
#define MCP251XFD_REG_INT_TBCIF BIT(2)
#define MCP251XFD_REG_INT_RXIF BIT(1)
#define MCP251XFD_REG_INT_TXIF BIT(0)
/* These IRQ flags must be cleared by SW in the CAN_INT register */
#define MCP251XFD_REG_INT_IF_CLEARABLE_MASK \
(MCP251XFD_REG_INT_IVMIF | MCP251XFD_REG_INT_WAKIF | MCP251XFD_REG_INT_CERRIF | \
MCP251XFD_REG_INT_SERRIF | MCP251XFD_REG_INT_MODIF)
#define MCP251XFD_REG_RXIF 0x20
#define MCP251XFD_REG_TXIF 0x24
#define MCP251XFD_REG_RXOVIF 0x28
#define MCP251XFD_REG_TXATIF 0x2c
#define MCP251XFD_REG_TXREQ 0x30
#define MCP251XFD_REG_TREC 0x34
#define MCP251XFD_REG_TREC_TXBO BIT(21)
#define MCP251XFD_REG_TREC_TXBP BIT(20)
#define MCP251XFD_REG_TREC_RXBP BIT(19)
#define MCP251XFD_REG_TREC_TXWARN BIT(18)
#define MCP251XFD_REG_TREC_RXWARN BIT(17)
#define MCP251XFD_REG_TREC_EWARN BIT(16)
#define MCP251XFD_REG_TREC_TEC_MASK GENMASK(15, 8)
#define MCP251XFD_REG_TREC_REC_MASK GENMASK(7, 0)
#define MCP251XFD_REG_BDIAG0 0x38
#define MCP251XFD_REG_BDIAG0_DTERRCNT_MASK GENMASK(31, 24)
#define MCP251XFD_REG_BDIAG0_DRERRCNT_MASK GENMASK(23, 16)
#define MCP251XFD_REG_BDIAG0_NTERRCNT_MASK GENMASK(15, 8)
#define MCP251XFD_REG_BDIAG0_NRERRCNT_MASK GENMASK(7, 0)
#define MCP251XFD_REG_BDIAG1 0x3c
#define MCP251XFD_REG_BDIAG1_DLCMM BIT(31)
#define MCP251XFD_REG_BDIAG1_ESI BIT(30)
#define MCP251XFD_REG_BDIAG1_DCRCERR BIT(29)
#define MCP251XFD_REG_BDIAG1_DSTUFERR BIT(28)
#define MCP251XFD_REG_BDIAG1_DFORMERR BIT(27)
#define MCP251XFD_REG_BDIAG1_DBIT1ERR BIT(25)
#define MCP251XFD_REG_BDIAG1_DBIT0ERR BIT(24)
#define MCP251XFD_REG_BDIAG1_TXBOERR BIT(23)
#define MCP251XFD_REG_BDIAG1_NCRCERR BIT(21)
#define MCP251XFD_REG_BDIAG1_NSTUFERR BIT(20)
#define MCP251XFD_REG_BDIAG1_NFORMERR BIT(19)
#define MCP251XFD_REG_BDIAG1_NACKERR BIT(18)
#define MCP251XFD_REG_BDIAG1_NBIT1ERR BIT(17)
#define MCP251XFD_REG_BDIAG1_NBIT0ERR BIT(16)
#define MCP251XFD_REG_BDIAG1_BERR_MASK \
(MCP251XFD_REG_BDIAG1_DLCMM | MCP251XFD_REG_BDIAG1_ESI | MCP251XFD_REG_BDIAG1_DCRCERR | \
MCP251XFD_REG_BDIAG1_DSTUFERR | MCP251XFD_REG_BDIAG1_DFORMERR | \
MCP251XFD_REG_BDIAG1_DBIT1ERR | MCP251XFD_REG_BDIAG1_DBIT0ERR | \
MCP251XFD_REG_BDIAG1_TXBOERR | MCP251XFD_REG_BDIAG1_NCRCERR | \
MCP251XFD_REG_BDIAG1_NSTUFERR | MCP251XFD_REG_BDIAG1_NFORMERR | \
MCP251XFD_REG_BDIAG1_NACKERR | MCP251XFD_REG_BDIAG1_NBIT1ERR | \
MCP251XFD_REG_BDIAG1_NBIT0ERR)
#define MCP251XFD_REG_BDIAG1_EFMSGCNT_MASK GENMASK(15, 0)
#define MCP251XFD_REG_TEFCON 0x40
#define MCP251XFD_REG_TEFCON_FSIZE_MASK GENMASK(28, 24)
#define MCP251XFD_REG_TEFCON_FRESET BIT(10)
#define MCP251XFD_REG_TEFCON_UINC BIT(8)
#define MCP251XFD_REG_TEFCON_TEFTSEN BIT(5)
#define MCP251XFD_REG_TEFCON_TEFOVIE BIT(3)
#define MCP251XFD_REG_TEFCON_TEFFIE BIT(2)
#define MCP251XFD_REG_TEFCON_TEFHIE BIT(1)
#define MCP251XFD_REG_TEFCON_TEFNEIE BIT(0)
#define MCP251XFD_REG_TEFSTA 0x44
#define MCP251XFD_REG_TEFSTA_TEFOVIF BIT(3)
#define MCP251XFD_REG_TEFSTA_TEFFIF BIT(2)
#define MCP251XFD_REG_TEFSTA_TEFHIF BIT(1)
#define MCP251XFD_REG_TEFSTA_TEFNEIF BIT(0)
#define MCP251XFD_REG_TEFUA 0x48
#define MCP251XFD_REG_TXQCON 0x50
#define MCP251XFD_REG_TXQCON_PLSIZE_MASK GENMASK(31, 29)
#define MCP251XFD_REG_TXQCON_PLSIZE_8 0
#define MCP251XFD_REG_TXQCON_PLSIZE_12 1
#define MCP251XFD_REG_TXQCON_PLSIZE_16 2
#define MCP251XFD_REG_TXQCON_PLSIZE_20 3
#define MCP251XFD_REG_TXQCON_PLSIZE_24 4
#define MCP251XFD_REG_TXQCON_PLSIZE_32 5
#define MCP251XFD_REG_TXQCON_PLSIZE_48 6
#define MCP251XFD_REG_TXQCON_PLSIZE_64 7
#define MCP251XFD_REG_TXQCON_FSIZE_MASK GENMASK(28, 24)
#define MCP251XFD_REG_TXQCON_TXAT_UNLIMITED 3
#define MCP251XFD_REG_TXQCON_TXAT_THREE_SHOT 1
#define MCP251XFD_REG_TXQCON_TXAT_ONE_SHOT 0
#define MCP251XFD_REG_TXQCON_TXAT_MASK GENMASK(22, 21)
#define MCP251XFD_REG_TXQCON_TXPRI_MASK GENMASK(20, 16)
#define MCP251XFD_REG_TXQCON_FRESET BIT(10)
#define MCP251XFD_REG_TXQCON_TXREQ BIT(9)
#define MCP251XFD_REG_TXQCON_UINC BIT(8)
#define MCP251XFD_REG_TXQCON_TXEN BIT(7)
#define MCP251XFD_REG_TXQCON_TXATIE BIT(4)
#define MCP251XFD_REG_TXQCON_TXQEIE BIT(2)
#define MCP251XFD_REG_TXQCON_TXQNIE BIT(0)
#define MCP251XFD_REG_TXQSTA 0x54
#define MCP251XFD_REG_TXQSTA_TXQCI_MASK GENMASK(12, 8)
#define MCP251XFD_REG_TXQSTA_TXABT BIT(7)
#define MCP251XFD_REG_TXQSTA_TXLARB BIT(6)
#define MCP251XFD_REG_TXQSTA_TXERR BIT(5)
#define MCP251XFD_REG_TXQSTA_TXATIF BIT(4)
#define MCP251XFD_REG_TXQSTA_TXQEIF BIT(2)
#define MCP251XFD_REG_TXQSTA_TXQNIF BIT(0)
#define MCP251XFD_REG_TXQUA 0x58
#define MCP251XFD_REG_FIFOCON(x) (0x50 + 0xc * (x))
#define MCP251XFD_REG_FIFOCON_PLSIZE_MASK GENMASK(31, 29)
#define MCP251XFD_REG_FIFOCON_PLSIZE_8 0
#define MCP251XFD_REG_FIFOCON_PLSIZE_12 1
#define MCP251XFD_REG_FIFOCON_PLSIZE_16 2
#define MCP251XFD_REG_FIFOCON_PLSIZE_20 3
#define MCP251XFD_REG_FIFOCON_PLSIZE_24 4
#define MCP251XFD_REG_FIFOCON_PLSIZE_32 5
#define MCP251XFD_REG_FIFOCON_PLSIZE_48 6
#define MCP251XFD_REG_FIFOCON_PLSIZE_64 7
#define MCP251XFD_REG_FIFOCON_FSIZE_MASK GENMASK(28, 24)
#define MCP251XFD_REG_FIFOCON_TXAT_MASK GENMASK(22, 21)
#define MCP251XFD_REG_FIFOCON_TXAT_ONE_SHOT 0
#define MCP251XFD_REG_FIFOCON_TXAT_THREE_SHOT 1
#define MCP251XFD_REG_FIFOCON_TXAT_UNLIMITED 3
#define MCP251XFD_REG_FIFOCON_TXPRI_MASK GENMASK(20, 16)
#define MCP251XFD_REG_FIFOCON_FRESET BIT(10)
#define MCP251XFD_REG_FIFOCON_TXREQ BIT(9)
#define MCP251XFD_REG_FIFOCON_UINC BIT(8)
#define MCP251XFD_REG_FIFOCON_TXEN BIT(7)
#define MCP251XFD_REG_FIFOCON_RTREN BIT(6)
#define MCP251XFD_REG_FIFOCON_RXTSEN BIT(5)
#define MCP251XFD_REG_FIFOCON_TXATIE BIT(4)
#define MCP251XFD_REG_FIFOCON_RXOVIE BIT(3)
#define MCP251XFD_REG_FIFOCON_TFERFFIE BIT(2)
#define MCP251XFD_REG_FIFOCON_TFHRFHIE BIT(1)
#define MCP251XFD_REG_FIFOCON_TFNRFNIE BIT(0)
#define MCP251XFD_REG_FIFOSTA(x) (0x54 + 0xc * (x))
#define MCP251XFD_REG_FIFOSTA_FIFOCI_MASK GENMASK(12, 8)
#define MCP251XFD_REG_FIFOSTA_TXABT BIT(7)
#define MCP251XFD_REG_FIFOSTA_TXLARB BIT(6)
#define MCP251XFD_REG_FIFOSTA_TXERR BIT(5)
#define MCP251XFD_REG_FIFOSTA_TXATIF BIT(4)
#define MCP251XFD_REG_FIFOSTA_RXOVIF BIT(3)
#define MCP251XFD_REG_FIFOSTA_TFERFFIF BIT(2)
#define MCP251XFD_REG_FIFOSTA_TFHRFHIF BIT(1)
#define MCP251XFD_REG_FIFOSTA_TFNRFNIF BIT(0)
#define MCP251XFD_REG_FIFOUA(x) (0x58 + 0xc * (x))
#define MCP251XFD_REG_BYTE_FLTCON(m) (0x1d0 + m)
#define MCP251XFD_REG_BYTE_FLTCON_FBP_MASK GENMASK(4, 0)
#define MCP251XFD_REG_BYTE_FLTCON_FLTEN BIT(7)
#define MCP251XFD_REG_FLTOBJ(x) (0x1f0 + 0x8 * (x))
#define MCP251XFD_REG_FLTOBJ_EXIDE BIT(30)
#define MCP251XFD_REG_FLTOBJ_SID11 BIT(29)
#define MCP251XFD_REG_FLTOBJ_EID_MASK GENMASK(28, 11)
#define MCP251XFD_REG_FLTOBJ_SID_MASK GENMASK(10, 0)
#define MCP251XFD_REG_FLTMASK(x) (0x1f4 + 0x8 * (x))
#define MCP251XFD_REG_MASK_MIDE BIT(30)
#define MCP251XFD_REG_MASK_MSID11 BIT(29)
#define MCP251XFD_REG_MASK_MEID_MASK GENMASK(28, 11)
#define MCP251XFD_REG_MASK_MSID_MASK GENMASK(10, 0)
/* Message Object */
#define MCP251XFD_OBJ_ID_SID11 BIT(29)
#define MCP251XFD_OBJ_ID_EID_MASK GENMASK(28, 11)
#define MCP251XFD_OBJ_ID_SID_MASK GENMASK(10, 0)
#define MCP251XFD_OBJ_FLAGS_SEQ_MCP2518FD_MASK GENMASK(31, 9)
#define MCP251XFD_OBJ_FLAGS_SEQ_MCP2517FD_MASK GENMASK(15, 9)
#define MCP251XFD_OBJ_FLAGS_SEQ_MASK MCP251XFD_OBJ_FLAGS_SEQ_MCP2518FD_MASK
#define MCP251XFD_OBJ_FLAGS_ESI BIT(8)
#define MCP251XFD_OBJ_FLAGS_FDF BIT(7)
#define MCP251XFD_OBJ_FLAGS_BRS BIT(6)
#define MCP251XFD_OBJ_FLAGS_RTR BIT(5)
#define MCP251XFD_OBJ_FLAGS_IDE BIT(4)
#define MCP251XFD_OBJ_FLAGS_DLC_MASK GENMASK(3, 0)
#define MCP251XFD_OBJ_FILHIT_MASK GENMASK(15, 11)
#define MCP251XFD_OBJ_DATA_OFFSET 2 /* offset to the data in sizeof(uint32_t) */
#define MCP251XFD_OBJ_HEADER_SIZE (MCP251XFD_OBJ_DATA_OFFSET * MCP251XFD_REG_SIZE)
#define MCP251XFD_REG_FRAME_EFF_SID_MASK GENMASK(28, 18)
#define MCP251XFD_REG_FRAME_EFF_EID_MASK GENMASK(17, 0)
/* MCP2517/18FD SFR */
#define MCP251XFD_REG_OSC 0xe00
#define MCP251XFD_REG_OSC_SCLKRDY BIT(12)
#define MCP251XFD_REG_OSC_OSCRDY BIT(10)
#define MCP251XFD_REG_OSC_PLLRDY BIT(8)
#define MCP251XFD_REG_OSC_CLKODIV_10 3
#define MCP251XFD_REG_OSC_CLKODIV_4 2
#define MCP251XFD_REG_OSC_CLKODIV_2 1
#define MCP251XFD_REG_OSC_CLKODIV_1 0
#define MCP251XFD_REG_OSC_CLKODIV_MASK GENMASK(6, 5)
#define MCP251XFD_REG_OSC_SCLKDIV BIT(4)
#define MCP251XFD_REG_OSC_LPMEN BIT(3) /* MCP2518FD only */
#define MCP251XFD_REG_OSC_OSCDIS BIT(2)
#define MCP251XFD_REG_OSC_PLLEN BIT(0)
#define MCP251XFD_REG_IOCON 0xe04
#define MCP251XFD_REG_IOCON_INTOD BIT(30)
#define MCP251XFD_REG_IOCON_SOF BIT(29)
#define MCP251XFD_REG_IOCON_TXCANOD BIT(28)
#define MCP251XFD_REG_IOCON_PM1 BIT(25)
#define MCP251XFD_REG_IOCON_PM0 BIT(24)
#define MCP251XFD_REG_IOCON_GPIO1 BIT(17)
#define MCP251XFD_REG_IOCON_GPIO0 BIT(16)
#define MCP251XFD_REG_IOCON_LAT1 BIT(9)
#define MCP251XFD_REG_IOCON_LAT0 BIT(8)
#define MCP251XFD_REG_IOCON_XSTBYEN BIT(6)
#define MCP251XFD_REG_IOCON_TRIS1 BIT(1)
#define MCP251XFD_REG_IOCON_TRIS0 BIT(0)
#define MCP251XFD_REG_CRC 0xe08
#define MCP251XFD_REG_CRC_FERRIE BIT(25)
#define MCP251XFD_REG_CRC_CRCERRIE BIT(24)
#define MCP251XFD_REG_CRC_FERRIF BIT(17)
#define MCP251XFD_REG_CRC_CRCERRIF BIT(16)
#define MCP251XFD_REG_CRC_IF_MASK GENMASK(17, 16)
#define MCP251XFD_REG_CRC_MASK GENMASK(15, 0)
#define MCP251XFD_REG_ECCCON 0xe0c
#define MCP251XFD_REG_ECCCON_PARITY_MASK GENMASK(14, 8)
#define MCP251XFD_REG_ECCCON_DEDIE BIT(2)
#define MCP251XFD_REG_ECCCON_SECIE BIT(1)
#define MCP251XFD_REG_ECCCON_ECCEN BIT(0)
#define MCP251XFD_REG_ECCSTAT 0xe10
#define MCP251XFD_REG_ECCSTAT_ERRADDR_MASK GENMASK(27, 16)
#define MCP251XFD_REG_ECCSTAT_IF_MASK GENMASK(2, 1)
#define MCP251XFD_REG_ECCSTAT_DEDIF BIT(2)
#define MCP251XFD_REG_ECCSTAT_SECIF BIT(1)
#define MCP251XFD_REG_DEVID 0xe14 /* MCP2518FD only */
#define MCP251XFD_REG_DEVID_ID_MASK GENMASK(7, 4)
#define MCP251XFD_REG_DEVID_REV_MASK GENMASK(3, 0)
/* SPI commands */
#define MCP251XFD_SPI_INSTRUCTION_RESET 0x0000
#define MCP251XFD_SPI_INSTRUCTION_WRITE 0x2000
#define MCP251XFD_SPI_INSTRUCTION_READ 0x3000
#define MCP251XFD_SPI_INSTRUCTION_WRITE_CRC 0xa000
#define MCP251XFD_SPI_INSTRUCTION_READ_CRC 0xb000
#define MCP251XFD_SPI_INSTRUCTION_WRITE_CRC_SAFE 0xc000
#define MCP251XFD_SPI_ADDRESS_MASK GENMASK(11, 0)
#define MCP251XFD_REG_FIFOCON_TO_STA(addr) (addr + 0x4)
#define MCP251XFD_REG_FLTCON(m) (0x1d0 + m)
struct mcp251xfd_txobj {
uint32_t id;
uint32_t flags;
uint8_t data[CAN_MAX_DLEN];
} __packed;
struct mcp251xfd_rxobj {
uint32_t id;
uint32_t flags;
#if defined(CONFIG_CAN_RX_TIMESTAMP)
uint32_t timestamp;
#endif
uint8_t data[CAN_MAX_DLEN];
} __packed;
struct mcp251xfd_tefobj {
uint32_t id;
uint32_t flags;
} __packed;
#define MCP251XFD_MAX_READ_FIFO_BUF_SIZE \
MAX((MCP251XFD_RX_FIFO_ITEM_SIZE * MCP251XFD_RX_FIFO_ITEMS), \
(MCP251XFD_TEF_FIFO_ITEM_SIZE * MCP251XFD_TEF_FIFO_ITEMS))
#define MCP251XFD_MAX_READ_CRC_BUF_SIZE \
(MCP251XFD_SPI_CRC_LEN + 2 * MCP251XFD_REG_SIZE)
#define MCP251XFD_SPI_BUF_SIZE \
MAX(MCP251XFD_MAX_READ_FIFO_BUF_SIZE, MCP251XFD_MAX_READ_CRC_BUF_SIZE)
#define MCP251XFD_SPI_HEADER_LEN (MCP251XFD_SPI_CMD_LEN + MCP251XFD_SPI_LEN_FIELD_LEN)
struct mcp251xfd_spi_data {
uint8_t _unused[4 - (MCP251XFD_SPI_HEADER_LEN % 4)]; /* so that buf is 4-byte aligned */
uint8_t header[MCP251XFD_SPI_HEADER_LEN]; /* contains spi_cmd and length field (if used) */
uint8_t buf[MCP251XFD_SPI_BUF_SIZE];
} __packed __aligned(4);
struct mcp251xfd_fifo {
uint32_t ram_start_addr;
uint16_t reg_fifocon_addr;
uint8_t capacity;
uint8_t item_size;
void (*msg_handler)(const struct device *dev, void *data);
};
struct mcp251xfd_data {
/* Interrupt Data */
struct gpio_callback int_gpio_cb;
struct k_thread int_thread;
k_thread_stack_t *int_thread_stack;
struct k_sem int_sem;
/* General */
enum can_state state;
can_state_change_callback_t state_change_cb;
void *state_change_cb_data;
struct k_mutex mutex;
/* TX Callback */
struct k_sem tx_sem;
uint32_t mailbox_usage;
struct mcp251xfd_mailbox mailbox[CONFIG_CAN_MCP251XFD_MAX_TX_QUEUE];
/* Filter Data */
uint64_t filter_usage;
struct can_filter filter[CONFIG_CAN_MAX_FILTER];
can_rx_callback_t rx_cb[CONFIG_CAN_MAX_FILTER];
void *cb_arg[CONFIG_CAN_MAX_FILTER];
const struct device *dev;
bool started;
uint8_t next_mcp251xfd_mode;
uint8_t current_mcp251xfd_mode;
int tdco;
can_mode_t mode;
struct mcp251xfd_spi_data spi_data;
};
struct mcp251xfd_timing_params {
uint8_t sjw;
uint8_t prop_seg;
uint8_t phase_seg1;
uint8_t phase_seg2;
uint32_t bus_speed;
uint16_t sample_point;
};
struct mcp251xfd_config {
/* spi configuration */
struct spi_dt_spec bus;
struct gpio_dt_spec int_gpio_dt;
uint32_t osc_freq;
/* IO Config */
bool sof_on_clko;
bool pll_enable;
uint8_t clko_div;
uint16_t timestamp_prescaler;
/* CAN Timing */
struct mcp251xfd_timing_params timing_params;
#if defined(CONFIG_CAN_FD_MODE)
struct mcp251xfd_timing_params timing_params_data;
#endif
/* CAN transceiver */
const struct device *phy;
uint32_t max_bitrate;
const struct device *clk_dev;
uint8_t clk_id;
struct mcp251xfd_fifo rx_fifo;
struct mcp251xfd_fifo tef_fifo;
};
#endif /* ZEPHYR_DRIVERS_CAN_MICROCHIP_MCP251XFD_H_ */

1088
drivers/can/can_mcp25xxfd.c

File diff suppressed because it is too large Load Diff

537
drivers/can/can_mcp25xxfd.h

@ -1,537 +0,0 @@ @@ -1,537 +0,0 @@
/*
* Copyright (c) 2020 Abram Early
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_CAN_MICROCHIP_MCP25XXFD_H_
#define ZEPHYR_DRIVERS_CAN_MICROCHIP_MCP25XXFD_H_
#include <drivers/can.h>
#define DEV_CFG(dev) ((const struct mcp25xxfd_config *const)(dev)->config)
#define DEV_DATA(dev) ((struct mcp25xxfd_data *const)(dev)->data)
#define MCP25XXFD_RAM_SIZE 2048
#define MCP25XXFD_PAYLOAD_SIZE CLAMP(ROUND_UP(CAN_MAX_DLEN, 4), 8, 64)
#if defined(CONFIG_CAN_TX_TIMESTAMP)
/* Note: This will be implemented with a future can_send overhaul */
#define MCP25XXFD_TEF_SIZE (CONFIG_CAN_MCP25XXFD_MAX_TX_QUEUE * (4 + 8))
#else
#define MCP25XXFD_TEF_SIZE (CONFIG_CAN_MCP25XXFD_MAX_TX_QUEUE * (0 + 8))
#endif
#define MCP25XXFD_TXFIFOS_SIZE (CONFIG_CAN_MCP25XXFD_MAX_TX_QUEUE * (8 + MCP25XXFD_PAYLOAD_SIZE))
#define MCP25XXFD_RXFIFO_MAX \
((MCP25XXFD_RAM_SIZE - (MCP25XXFD_TEF_SIZE + MCP25XXFD_TXFIFOS_SIZE)))
#if defined(CONFIG_CAN_RX_TIMESTAMP)
#define MCP25XXFD_RXFIFO_ELEMENT_SIZE (4 + 8 + MCP25XXFD_PAYLOAD_SIZE)
#else
#define MCP25XXFD_RXFIFO_ELEMENT_SIZE (0 + 8 + MCP25XXFD_PAYLOAD_SIZE)
#endif
#define MCP25XXFD_RXFIFO_LENGTH \
MIN(MCP25XXFD_RXFIFO_MAX / MCP25XXFD_RXFIFO_ELEMENT_SIZE, 32)
#define MCP25XXFD_RXFIFO_SIZE (MCP25XXFD_RXFIFO_LENGTH * MCP25XXFD_RXFIFO_ELEMENT_SIZE)
#define MCP25XXFD_TXFIFOS CONFIG_CAN_MCP25XXFD_MAX_TX_QUEUE
#define MCP25XXFD_RXFIFO_IDX CONFIG_CAN_MCP25XXFD_MAX_TX_QUEUE
BUILD_ASSERT(MCP25XXFD_RXFIFO_LENGTH >= 1,
"Cannot fit RX FIFO into MCP25xxFD RAM");
struct mcp25xxfd_mailbox {
can_tx_callback_t cb;
void *cb_arg;
struct k_sem tx_sem;
};
struct mcp25xxfd_data {
/* SPI Data */
const struct device *spi;
struct spi_config spi_cfg;
#if DT_INST_SPI_DEV_HAS_CS_GPIOS(0)
struct spi_cs_control spi_cs_ctrl;
#endif /* DT_INST_SPI_DEV_HAS_CS_GPIOS(0) */
/* Interrupt Data */
const struct device *int_gpio;
struct gpio_callback int_gpio_cb;
struct k_thread int_thread;
k_thread_stack_t *int_thread_stack;
struct k_sem int_sem;
uint8_t int_pin;
/* General */
enum can_state state;
can_state_change_isr_t state_change_isr;
struct k_mutex mutex;
struct k_sem mode_sem;
/* TX Callback */
struct k_sem tx_sem;
uint32_t mailbox_usage;
struct mcp25xxfd_mailbox mailbox[CONFIG_CAN_MCP25XXFD_MAX_TX_QUEUE];
/* Filter Data */
uint64_t filter_usage;
struct zcan_filter filter[CONFIG_CAN_MAX_FILTER];
can_rx_callback_t rx_cb[CONFIG_CAN_MAX_FILTER];
void *cb_arg[CONFIG_CAN_MAX_FILTER];
};
struct mcp25xxfd_config {
/* SPI Config */
const char *spi_port;
uint32_t spi_freq;
uint8_t spi_slave;
uint8_t spi_cs_pin;
uint8_t spi_cs_flags;
const char *spi_cs_port;
/* Interrupt Config */
uint8_t int_pin;
const char *int_port;
size_t int_thread_stack_size;
int int_thread_priority;
uint32_t osc_freq;
/* CAN Timing */
uint8_t tq_sjw;
uint8_t tq_prop;
uint8_t tq_bs1;
uint8_t tq_bs2;
uint32_t bus_speed;
uint16_t sample_point;
/* IO Config */
bool sof_on_clko;
uint8_t clko_div;
#if defined(CONFIG_CAN_FD_MODE)
/* CAN-FD Timing */
uint8_t tq_sjw_data;
uint8_t tq_prop_data;
uint8_t tq_bs1_data;
uint8_t tq_bs2_data;
uint32_t bus_speed_data;
uint16_t sample_point_data;
#endif
};
/* MCP25XXFD Opcodes */
#define MCP25XXFD_OPCODE_RESET 0x00
#define MCP25XXFD_OPCODE_WRITE 0x02
#define MCP25XXFD_OPCODE_READ 0x03
/* MCP25XXFD Operation Modes */
#define MCP25XXFD_OPMODE_NORMAL_CANFD 0b000
#define MCP25XXFD_OPMODE_SLEEP 0b001
#define MCP25XXFD_OPMODE_INT_LOOPBACK 0b010
#define MCP25XXFD_OPMODE_LISTEN_ONLY 0b011
#define MCP25XXFD_OPMODE_CONFIGURATION 0b100
#define MCP25XXFD_OPMODE_EXT_LOOPBACK 0b101
#define MCP25XXFD_OPMODE_NORMAL_CAN2 0b110
#define MCP25XXFD_OPMODE_RESTRICTED 0b110
#define MCP25XXFD_WFT_T00FILTER 0b00
#define MCP25XXFD_WFT_T01FILTER 0b01
#define MCP25XXFD_WFT_T10FILTER 0b10
#define MCP25XXFD_WFT_T11FILTER 0b11
#define MCP25XXFD_TDCMOD_AUTO 0b10
#define MCP25XXFD_TDCMOD_MANUAL 0b01
#define MCP25XXFD_TDCMOD_DISABLED 0b00
/* MCP25XXFD Registers */
#define MCP25XXFD_REG_CON 0x000
union mcp25xxfd_con {
struct {
uint32_t DNCNT : 5; /* Device Net Filter Bit Number */
uint32_t ISOCRCEN : 1; /* Enable ISO CRC in CAN FD Frames */
uint32_t PXEDIS : 1; /* Protocol Exception Event Detection Disabled */
uint32_t res0 : 1;
uint32_t WAKFIL : 1; /* Enable CAN Bus Line Wake-up Filter */
uint32_t WFT : 2; /* Selectable Wake-up Filter Time */
uint32_t BUSY : 1; /* CAN Module is Busy */
uint32_t BRSDIS : 1; /* Bit Rate Switching Disable */
uint32_t res1 : 3;
uint32_t RTXAT : 1; /* Restrict Retransmission Attempts */
uint32_t ESIGM : 1; /* Transmit ESI in Gateway Mode */
uint32_t SERR2LOM : 1; /* Transition to Listen Only Mode on System Error */
uint32_t STEF : 1; /* Store in Transmit Event FIFO */
uint32_t TXQEN : 1; /* Enable Transmit Queue */
uint32_t OPMOD : 3; /* Operation Mode Status */
uint32_t REQMOD : 3; /* Request Operation Mode */
uint32_t ABAT : 1; /* Abort All Pending Transmissions */
uint32_t TXBWS : 4; /* Transmit Bandwidth Sharing */
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_NBTCFG 0x004
union mcp25xxfd_nbtcfg {
struct {
uint32_t SJW : 7; /* Synchronization Jump Width */
uint32_t res0 : 1;
uint32_t TSEG2 : 7; /* Time Segment 2 (Phase Segment 2) */
uint32_t res1 : 1;
uint32_t TSEG1 : 8; /* Time Segment 1 (Propagation Segment + Phase Segment 1) */
uint32_t BRP : 8; /* Baud Rate Prescaler */
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_DBTCFG 0x008
union mcp25xxfd_dbtcfg {
struct {
uint32_t SJW : 4; /* Synchronization Jump Width */
uint32_t res0 : 4;
uint32_t TSEG2 : 4; /* Time Segment 2 (Phase Segment 2) */
uint32_t res1 : 4;
uint32_t TSEG1 : 5; /* Time Segment 1 (Propagation Segment + Phase Segment 1) */
uint32_t res2 : 3;
uint32_t BRP : 8; /* Baud Rate Prescaler */
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_TDC 0x00C
union mcp25xxfd_tdc {
struct {
uint32_t TDCV : 6; /* Transmitter Delay Compensation Value */
uint32_t res0 : 2;
uint32_t TDCO : 7; /* Transmitter Delay Compensation Offset */
uint32_t res1 : 1;
uint32_t TDCMOD : 2; /* Transmitter Delay Compensation Mode */
uint32_t res2 : 6;
uint32_t SID11EN : 1; /* Enable 12-Bit SID in CAN FD Base Format Messages */
uint32_t EDGFLTEN : 1; /* Enable Edge Filtering during Bus Integration state */
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_TSCON 0x014
union mcp25xxfd_tscon {
struct {
uint32_t TBCPRE : 10; /* Time Base Counter Prescaler */
uint32_t res0 : 6;
uint32_t TBCEN : 1; /* Time Base Counter Enable */
uint32_t TSEOF : 1; /* 0: Beginning (See TSREF) / 1: Frame is considered valid */
uint32_t TSRES : 1; /* Timestamp Sample Point Bit (0: SP of SOF / 1: SP of bit following FDF on FD frames) */
uint32_t res1 : 13;
};
uint32_t word;
uint8_t bytes[4];
};
#define MCP25XXFD_REG_VEC 0x018
union mcp25xxfd_vec {
struct {
uint32_t ICODE : 7; /* Interrupt Flag Code */
uint32_t res0 : 1;
uint32_t FILHIT : 5; /* Filter Hit Number */
uint32_t res1 : 3;
uint32_t TXCODE : 7; /* Transmit Interrupt Flag Code */
uint32_t res2 : 1;
uint32_t RXCODE : 7; /* Receive Interrupt Flag Code */
uint32_t res3 : 1;
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_INT 0x01C
union mcp25xxfd_int {
struct {
uint32_t TXIF : 1; /* Transmit FIFO Interrupt Flag */
uint32_t RXIF : 1; /* Receive FIFO Interrupt Flag */
uint32_t TCBIF : 1; /* Time Base Counter Interrupt Flag */
uint32_t MODIF : 1; /* Mode Change Interrupt Flag */
uint32_t TEFIF : 1; /* Transmit Event FIFO Interrupt Flag */
uint32_t res0 : 3;
uint32_t ECCIF : 1; /* ECC Error Interrupt Flag */
uint32_t SPICRCIF : 1; /* SPI CRC Error Interrupt Flag */
uint32_t TXATIF : 1; /* Transmit Attempt Interrupt Flag */
uint32_t RXOVIF : 1; /* Receive FIFO Overflow Interrupt Flag */
uint32_t SERRIF : 1; /* System Error Interrupt Flag */
uint32_t CERRIF : 1; /* CAN Bus Error Interrupt Flag */
uint32_t WAKIF : 1; /* Bus Wake Up Interrupt Flag */
uint32_t IVMIF : 1; /* Invalid Message Interrupt Flag */
uint32_t TXIE : 1; /* Transmit FIFO Interrupt Enable */
uint32_t RXIE : 1; /* Receive FIFO Interrupt Enable */
uint32_t TBCIE : 1; /* Time Base Counter Interrupt Enable */
uint32_t MODIE : 1; /* Mode Change Interrupt Enable */
uint32_t TEFIE : 1; /* Transmit Event FIFO Interrupt Enable */
uint32_t res1 : 3;
uint32_t ECCIE : 1; /* ECC Error Interrupt Enable */
uint32_t SPICRCIE : 1; /* SPI CRC Error Interrupt Enable */
uint32_t TXATIE : 1; /* Transmit Attempt Interrupt Enable */
uint32_t RXOVIE : 1; /* Receive FIFO Overflow Interrupt Enable */
uint32_t SERRIE : 1; /* System Error Interrupt Enable */
uint32_t CERRIE : 1; /* CAN Bus Error Interrupt Enable */
uint32_t WAKIE : 1; /* Bus Wake Up Interrupt Enable */
uint32_t IVMIE : 1; /* Invalid Message Interrupt Enable */
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_INTREGS MCP25XXFD_REG_VEC
union mcp25xxfd_intregs {
struct {
union mcp25xxfd_vec vec; /* Interrupt Vector Codes */
union mcp25xxfd_int ints; /* Interrupt Enables/Flags */
uint32_t rxif; /* FIFO RXIF Interrupt Flags */
uint32_t txif; /* FIFO TXIF Interrupt Flags */
uint32_t rxovif; /* FIFO RXOVIF Interrupt Flags */
uint32_t txatif; /* FIFO TXATIF Interrupt Flags */
};
uint32_t words[6];
};
#define MCP25XXFD_REG_TREC 0x034
union mcp25xxfd_trec {
struct {
uint32_t REC : 8; /* Receive Error Counter */
uint32_t TEC : 8; /* Transmit Error Counter */
uint32_t EWARN : 1; /* Transmitter or Receiver is in Error Warning State */
uint32_t RXWARN : 1; /* Receiver is in Error Warning State */
uint32_t TXWARN : 1; /* Transmitter is in Error Warning State */
uint32_t RXBP : 1; /* Receiver in Error Passive State */
uint32_t TXBP : 1; /* Transmitter in Error Passive State bit */
uint32_t TXBO : 1; /* Transmitter in Bus Off State */
uint32_t res0 : 10;
};
uint32_t word;
uint8_t bytes[4];
};
#define MCP25XXFD_REG_BDIAG1 0x3C
union mcp25xxfd_bdiag1 {
struct {
uint32_t EFMSGCNT : 16;
uint32_t NBIT0ERR : 1;
uint32_t NBIT1ERR : 1;
uint32_t NACKERR : 1;
uint32_t NFORMERR : 1;
uint32_t NSTUFERR : 1;
uint32_t NCRCERR : 1;
uint32_t res0 : 1;
uint32_t TXBOERR : 1;
uint32_t DBIT0ERR : 1;
uint32_t DBIT1ERR : 1;
uint32_t res1 : 1;
uint32_t DFORMERR : 1;
uint32_t DSTUFERR : 1;
uint32_t DCRCERR : 1;
uint32_t ESI : 1;
uint32_t DLCMM : 1;
};
uint32_t word;
uint8_t byte[4];
};
/* The FIFOCON, FIFOSTA, and FIFOUA registers are almost identical to their TEF and TXQ counterparts. */
#define MCP25XXFD_REG_TEFCON 0x040
#define MCP25XXFD_REG_TXQCON 0x050
#define MCP25XXFD_REG_FIFOCON(m) (MCP25XXFD_REG_TXQCON + (m) * 0xC)
union mcp25xxfd_fifocon {
struct {
uint32_t FNEIE : 1; /* FIFO Not Full/Not Empty Interrupt Enable */
uint32_t FHIE : 1; /* FIFO Half Empty/Full Interrupt Enable */
uint32_t FFIE : 1; /* FIFO Empty/Full Interrupt Enable */
uint32_t OVIE : 1; /* FIFO Overflow Interrupt Enable */
uint32_t TXATIE : 1; /* FIFO TX Attempts Exhuasted Interrupt Enable */
uint32_t TSEN : 1; /* FIFO Timestamp Enable */
uint32_t RTREN : 1; /* FIFO Auto RTR Enable */
uint32_t TXEN : 1; /* FIFO Transmit Enable */
uint32_t UINC : 1; /* FIFO Increment Head */
uint32_t TXREQ : 1; /* FIFO Message Send Request */
uint32_t FRESET : 1; /* FIFO Reset */
uint32_t res0 : 5;
uint32_t TXPRI : 5; /* Transmit Priority */
uint32_t TXAT : 2; /* Retransmission Attempts */
uint32_t res1 : 1;
uint32_t FSIZE : 5; /* FIFO Size */
uint32_t PLSIZE : 3; /* Payload Size */
};
uint32_t word;
uint8_t bytes[4];
};
#define MCP25XXFD_REG_TEFSTA 0x044
#define MCP25XXFD_REG_TXQSTA 0x054
#define MCP25XXFD_REG_FIFOSTA(m) (MCP25XXFD_REG_TXQSTA + (m) * 0xC)
union mcp25xxfd_fifosta {
struct {
uint32_t FNEIF : 1; /* FIFO Not Full/Not Empty Interrupt Flag */
uint32_t FHIF : 1; /* FIFO Half Empty/Full Interrupt Flag */
uint32_t FFIF : 1; /* FIFO Empty/Full Interrupt Flag */
uint32_t OVIF : 1; /* FIFO Overflow Interrupt Flag */
uint32_t TXATIF : 1; /* FIFO TX Attempts Exhuasted Interrupt Flag */
uint32_t TXERR : 1; /* Transmission Error Status */
uint32_t TXLARB : 1; /* Message Lost Arbitration Status */
uint32_t TXABT : 1; /* Message Aborted Status */
uint32_t FIFOCI : 5; /* FIFO Message Index */
};
uint32_t word;
uint8_t bytes[4];
};
#define MCP25XXFD_REG_TEFUA 0x048
#define MCP25XXFD_REG_TXQUA 0x058
#define MCP25XXFD_REG_FIFOUA(m) (MCP25XXFD_REG_TXQUA + (m) * 0xC)
union mcp25xxfd_fifo {
struct {
union mcp25xxfd_fifocon con; /* FIFO Control Register */
union mcp25xxfd_fifosta sta; /* FIFO Status Register */
uint32_t ua; /* FIFO User Address Register */
};
uint32_t words[3];
};
#define MCP21518FD_REG_FLTCON(m) (0x1D0 + m)
union mcp25xxfd_fltcon {
struct {
uint32_t FLTBP : 5;
uint32_t res : 2;
uint32_t FLTEN : 1;
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_FLTOBJ(m) (0x1F0 + ((m) * 8))
union mcp25xxfd_fltobj {
struct {
uint32_t SID : 11;
uint32_t EID : 18;
uint32_t SID11 : 1;
uint32_t EXIDE : 1;
uint32_t res0 : 1;
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_MASK(m) (0x1F4 + ((m) * 8))
union mcp25xxfd_mask {
struct {
uint32_t MSID : 11;
uint32_t MEID : 18;
uint32_t MSID11 : 1;
uint32_t MIDE : 1;
uint32_t res0 : 1;
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_OSC 0xE00
union mcp25xxfd_osc {
struct {
uint32_t PLLEN : 1; /* PLL Enable (0: Clock from XTAL, 1: Clock from 10x PLL) */
uint32_t res0 : 1;
uint32_t OSCDIS : 1; /* Clock (Oscillator) Disable */
uint32_t LPMEN : 1; /* Low Power Mode (LPM) Enable */
uint32_t SCLKDIV : 1; /* System Clock Divisor (0: 1/1, 1: 1/2) */
uint32_t CLKODIV : 2; /* Clock Output Divisor (0: 1/1, 1: 1/2, 2: 1/4, 3: 1/10) */
uint32_t res1 : 1;
uint32_t PLLRDY : 1; /* PLL Ready (0: Not Ready, 1: Locked) */
uint32_t res2 : 1;
uint32_t OSCRDY : 1; /* Clock Ready (0: Not Ready/Off, 1: Running/Stable) */
uint32_t res3 : 1;
uint32_t SCLKRDY : 1; /* Synchronized SCLKDIV Bit (0: SCLKDIV 0, 1: SCLKDIV 1) */
uint32_t res4 : 19;
};
uint32_t word;
uint8_t byte[4];
};
#define MCP25XXFD_REG_IOCON 0xE04
union mcp25xxfd_iocon {
struct {
uint32_t TRIS0 : 1; /* GPIO0 Data Direction (0: Output, 1: Input) */
uint32_t TRIS1 : 1; /* GPIO1 Data Direction (0: Output, 1: Input) */
uint32_t res0 : 4;
uint32_t XSTBYEN : 1; /* Enable Transiever Standby Pin Control */
uint32_t res1 : 1;
uint32_t LAT0 : 1; /* GPIO0 Latch (0: Low, 1: High) */
uint32_t LAT1 : 1; /* GPIO1 Latch (0: Low, 1: High) */
uint32_t res2 : 6;
uint32_t GPIO0 : 1; /* GPIO0 Status (0: < VIL, 1: > VIH) */
uint32_t GPIO1 : 1; /* GPIO1 Status (0: < VIL, 1: > VIH) */
uint32_t res3 : 6;
uint32_t PM0 : 1; /* GPIO0 Pin Mode (0: INT0, 1: GPIO0) */
uint32_t PM1 : 1; /* GPIO1 Pin Mode (0: INT1, 1: GPIO1) */
uint32_t res4 : 2;
uint32_t TXCANOD : 1; /* TXCAN Drive Mode (0: Push/Pull, 1: Open Drain) */
uint32_t SOF : 1; /* Start-Of-Frame Signal (0: Clock on CLKO, 1: SOF on CLKO) */
uint32_t INTOD : 1; /* Interrupt Pins Drive Mode (0: Push/Pull, 1: Open Drain) */
uint32_t res5 : 1;
};
uint32_t word;
uint8_t byte[4];
};
/* MCP25XXFD Objects */
struct mcp25xxfd_txobj {
uint32_t SID : 11;
uint32_t EID : 18;
uint32_t SID11 : 1;
uint32_t res0 : 2;
uint32_t DLC : 4; /* Data Length Code */
uint32_t IDE : 1; /* Indentifier Extension Flag */
uint32_t RTR : 1; /* Remote Transmission Request */
uint32_t BRS : 1; /* Bit Rate Switch Enable */
uint32_t FDF : 1; /* FD Frame */
uint32_t ESI : 1; /* Error Status Indicator */
uint32_t SEQ : 23;
uint8_t DATA[CAN_MAX_DLEN];
};
struct mcp25xxfd_rxobj {
uint32_t SID : 11;
uint32_t EID : 18;
uint32_t SID11 : 1;
uint32_t res0 : 2;
uint32_t DLC : 4; /* Data Length Code */
uint32_t IDE : 1; /* Indentifier Extension Flag */
uint32_t RTR : 1; /* Remote Transmission Request */
uint32_t BRS : 1; /* Bit Rate Switch Enable */
uint32_t FDF : 1; /* FD Frame */
uint32_t ESI : 1; /* Error Status Indicator */
uint32_t res1 : 2;
uint32_t FILHIT : 5;
uint32_t res2 : 16;
#if defined(CONFIG_CAN_RX_TIMESTAMP)
uint32_t RXMSGTS : 32;
#endif
uint8_t DATA[CAN_MAX_DLEN];
};
struct mcp25xxfd_tefobj {
uint32_t SID : 11;
uint32_t EID : 18;
uint32_t SID11 : 1;
uint32_t res0 : 2;
uint32_t DLC : 4; /* Data Length Code */
uint32_t IDE : 1; /* Indentifier Extension Flag */
uint32_t RTR : 1; /* Remote Transmission Request */
uint32_t BRS : 1; /* Bit Rate Switch Enable */
uint32_t FDF : 1; /* FD Frame */
uint32_t ESI : 1; /* Error Status Indicator */
uint32_t SEQ : 23;
};
#endif /* ZEPHYR_DRIVERS_CAN_MICROCHIP_MCP25XXFD_H_ */

80
dts/bindings/can/microchip,mcp251xfd.yaml

@ -0,0 +1,80 @@ @@ -0,0 +1,80 @@
# Copyright (c) 2020 Abram Early
# SPDX-License-Identifier: Apache-2.0
description: |
Microchip MCP251XFD SPI CAN-FD controller
The MCP251XFD node is defined on an SPI bus. An example
configuration is:
&mikrobus_spi {
cs-gpios = <&mikrobus_header 2 GPIO_ACTIVE_LOW>;
mcp2518fd_mikroe_mcp2518fd_click: mcp2518fd@0 {
compatible = "microchip,mcp251xfd";
status = "okay";
spi-max-frequency = <18000000>;
int-gpios = <&mikrobus_header 7 GPIO_ACTIVE_LOW>;
reg = <0x0>;
osc-freq = <40000000>;
bus-speed = <125000>;
sample-point = <875>;
bus-speed-data = <1000000>;
sample-point-data = <875>;
};
};
compatible: "microchip,mcp251xfd"
include: [spi-device.yaml, can-fd-controller.yaml]
properties:
osc-freq:
type: int
required: true
description: Frequency of the external oscillator in Hz.
int-gpios:
type: phandle-array
required: true
description: |
The interrupt signal from the controller is active low in push-pull mode.
The property value should ensure the flags properly describe the signal
that is presented to the driver.
pll-enable:
type: boolean
description: |
Enables controller PLL, which multiples input clock frequency x10.
This parameter also implicity sets whether the clock is from the PLL
output or directly from the oscillator.
If this option is enabled the clock source is the PLL, otherwise its
the oscillator.
timestamp-prescaler:
type: int
default: 1
description: |
Prescaler value for computing the timestamps of received messages.
The timestamp counter is derived from the internal clock divided by this value.
Valid range is [1, 1024].
sof-on-clko:
type: boolean
description: |
Output start-of-frame (SOF) signal on the CLKO pin every time
a Start bit of a CAN message is transmitted or received. If this option
is not set, then an internal clock (typically 40MHz or 20MHz) will be
output on CLKO pin instead.
clko-div:
type: int
description: The factor to divide the system clock for CLKO pin.
default: 10
enum:
- 1
- 2
- 4
- 10

40
dts/bindings/can/microchip,mcp25xxfd.yaml

@ -1,40 +0,0 @@ @@ -1,40 +0,0 @@
# Copyright (c) 2020 Abram Early
# SPDX-License-Identifier: Apache-2.0
description: MCP25XXFD SPI CAN-FD controller
compatible: "microchip,mcp25xxfd"
include: [spi-device.yaml, can-fd-controller.yaml]
properties:
osc-freq:
type: int
required: true
description: Frequency of the external oscillator
int-gpios:
type: phandle-array
required: true
description: >
Interrupt pin.
This pin signals active low when produced by the controller. The
property value should ensure the flags properly describe the signal
that is presented to the driver.
reg:
type: array
required: true
sof-on-clko:
type: boolean
required: false
description: Output SOF signal on CLKO pin
clko-div:
type: int
required: false
description: The factor to divide the system clock for CLKO
default: 10
enum:
- 1
- 2
- 4
- 10
Loading…
Cancel
Save