drivers: can: Implement stm32fd driver

This driver is the SoC specific implementation of the
Bosch M_CAN IP.

Signed-off-by: Alexander Wachter <alexander@wachter.cloud>
diff --git a/drivers/can/Kconfig.stm32fd b/drivers/can/Kconfig.stm32fd
index 030a494..3434f84 100644
--- a/drivers/can/Kconfig.stm32fd
+++ b/drivers/can/Kconfig.stm32fd
@@ -1,9 +1,17 @@
 # STM32 CAN configuration options
-if CAN_MCAN && SOC_SERIES_STM32G4X
+
+# Copyright (c) 2020 Alexander Wachter
+# SPDX-License-Identifier: Apache-2.0
+
+DT_COMPAT_STM32_FDCAN := st,stm32-fdcan
 
 config CAN_STM32FD
-	bool
-	default y
+	bool "STM32 FDCAN driver"
+	default $(dt_compat_enabled,$(DT_COMPAT_STM32_FDCAN))
+	select CAN_MCAN
+	select USE_STM32_LL_RCC
+
+if CAN_STM32FD
 
 config CAN_MAX_STD_ID_FILTER
 	int "Maximum number of std ID filters"
@@ -21,15 +29,14 @@
 	  Defines the maximum number of filters with extended ID (29-bit)
 	  that can be attached.
 
-config CAN_CKDIV
-	int "CKDIV register value"
-	range 0 15
-	default 0
+config CAN_STM32_CLOCK_DIVISOR
+	int "CAN clock divisor"
+	range 1 30
+	default 1
 	help
-	  This value is written to the CKDIV register.
-	  The APB clock is divided according to this value before it is feed to
-	  CAN core. Note that the the divider affects all CAN controllers.
-	  The values of the register are multiplied by two and zero corresponds
-	  to one. The value six, for example results in a clock divided by 12.
+	  The APB clock is divided by this value (stored in CKDIV register)
+	  before it is fed to the CAN core.
+	  Note that the the divisor affects all CAN controllers.
+	  Allowed values: 1 or 2 * n, where n <= 15.
 
-endif #CAN_MCAN
\ No newline at end of file
+endif #CAN_STM32FD
diff --git a/drivers/can/can_mcan.c b/drivers/can/can_mcan.c
index deb15fa..f1526df 100644
--- a/drivers/can/can_mcan.c
+++ b/drivers/can/can_mcan.c
@@ -86,6 +86,8 @@
 				timing->phase_seg2 > 0);
 		__ASSERT_NO_MSG(timing->prescaler <= 0x200 &&
 				timing->prescaler > 0);
+		__ASSERT_NO_MSG(timing->sjw <= 0x80 && timing->sjw > 0);
+
 		can->nbtp = (((uint32_t)timing->phase_seg1 - 1UL) & 0xFF) <<
 				CAN_MCAN_NBTP_NTSEG1_POS |
 			    (((uint32_t)timing->phase_seg2 - 1UL) & 0x7F) <<
@@ -105,6 +107,8 @@
 				timing_data->phase_seg2 > 0);
 		__ASSERT_NO_MSG(timing_data->prescaler <= 20 &&
 				timing_data->prescaler > 0);
+		__ASSERT_NO_MSG(timing_data->sjw <= 0x80 &&
+				timing_data->sjw > 0);
 
 		can->dbtp = (((uint32_t)timing_data->phase_seg1 - 1UL) & 0x1F) <<
 				CAN_MCAN_DBTP_DTSEG1_POS |
@@ -247,12 +251,12 @@
 	can->txefc = ((uint32_t)msg_ram->tx_event_fifo & CAN_MCAN_TXEFC_EFSA_MSK) |
 		     (ARRAY_SIZE(msg_ram->tx_event_fifo) <<
 		     CAN_MCAN_TXEFC_EFS_POS);
-	can->txbc = ((uint32_t)msg_ram->tx_fifo & CAN_MCAN_TXBC_TBSA) |
-		    (ARRAY_SIZE(msg_ram->tx_fifo) << CAN_MCAN_TXBC_TFQS_POS);
-	if (sizeof(msg_ram->tx_fifo[0].data) <= 24) {
-		can->txesc = (sizeof(msg_ram->tx_fifo[0].data) - 8) / 4;
+	can->txbc = ((uint32_t)msg_ram->tx_buffer & CAN_MCAN_TXBC_TBSA) |
+		    (ARRAY_SIZE(msg_ram->tx_buffer) << CAN_MCAN_TXBC_TFQS_POS);
+	if (sizeof(msg_ram->tx_buffer[0].data) <= 24) {
+		can->txesc = (sizeof(msg_ram->tx_buffer[0].data) - 8) / 4;
 	} else {
-		can->txesc = (sizeof(msg_ram->tx_fifo[0].data) - 32) / 16 + 5;
+		can->txesc = (sizeof(msg_ram->tx_buffer[0].data) - 32) / 16 + 5;
 	}
 
 	if (sizeof(msg_ram->rx_fifo0[0].data) <= 24) {
@@ -612,7 +616,7 @@
 {
 	struct can_mcan_reg  *can = cfg->can;
 	size_t data_length = can_dlc_to_bytes(frame->dlc);
-	struct can_mcan_tx_fifo_hdr tx_hdr = {
+	struct can_mcan_tx_buffer_hdr tx_hdr = {
 		.rtr = frame->rtr  == CAN_REMOTEREQUEST,
 		.xtd = frame->id_type == CAN_EXTENDED_IDENTIFIER,
 		.esi = 0,
@@ -675,10 +679,10 @@
 		tx_hdr.ext_id = frame->id;
 	}
 
-	msg_ram->tx_fifo[put_idx].hdr = tx_hdr;
+	msg_ram->tx_buffer[put_idx].hdr = tx_hdr;
 
 	for (src = frame->data_32,
-		dst = msg_ram->tx_fifo[put_idx].data_32,
+		dst = msg_ram->tx_buffer[put_idx].data_32,
 		end = dst + CAN_DIV_CEIL(data_length, sizeof(uint32_t));
 		dst < end;
 		src++, dst++) {
diff --git a/drivers/can/can_mcan.h b/drivers/can/can_mcan.h
index 0942f1e..33bc889 100644
--- a/drivers/can/can_mcan.h
+++ b/drivers/can/can_mcan.h
@@ -30,7 +30,7 @@
 	union {
 		struct {
 			volatile uint32_t ext_id : 29; /* Extended Identifier */
-			volatile uint32_t rtr    :  1; /* Retmote Transmission Request*/
+			volatile uint32_t rtr    :  1; /* Remote Transmission Request*/
 			volatile uint32_t xtd    :  1; /* Extended identifier */
 			volatile uint32_t esi    :  1; /* Error state indicator */
 		};
@@ -63,7 +63,7 @@
 	volatile uint8_t cnt : 3;
 } __packed;
 
-struct can_mcan_tx_fifo_hdr {
+struct can_mcan_tx_buffer_hdr {
 	union {
 		struct {
 			volatile uint32_t ext_id : 29; /* Identifier */
@@ -86,8 +86,8 @@
 	struct can_mcan_mm mm; /* Message marker */
 } __packed;
 
-struct can_mcan_tx_fifo {
-	struct can_mcan_tx_fifo_hdr hdr;
+struct can_mcan_tx_buffer {
+	struct can_mcan_tx_buffer_hdr hdr;
 	union {
 		volatile uint8_t  data[64];
 		volatile uint32_t data_32[16];
@@ -152,7 +152,7 @@
 	volatile struct can_mcan_rx_fifo rx_fifo1[NUM_RX_FIFO1_ELEMENTS];
 	volatile struct can_mcan_rx_fifo rx_buffer[NUM_RX_BUF_ELEMENTS];
 	volatile struct can_mcan_tx_event_fifo tx_event_fifo[NUM_TX_BUF_ELEMENTS];
-	volatile struct can_mcan_tx_fifo tx_fifo[NUM_TX_BUF_ELEMENTS];
+	volatile struct can_mcan_tx_buffer tx_buffer[NUM_TX_BUF_ELEMENTS];
 } __packed;
 
 struct can_mcan_data {
diff --git a/drivers/can/can_stm32fd.c b/drivers/can/can_stm32fd.c
index c81d467..43256d9 100644
--- a/drivers/can/can_stm32fd.c
+++ b/drivers/can/can_stm32fd.c
@@ -5,20 +5,287 @@
  */
 
 #include <drivers/can.h>
+#include <kernel.h>
+#include <soc.h>
+#include <stm32_ll_rcc.h>
+#include "can_stm32fd.h"
+#include <pinmux/stm32/pinmux_stm32.h>
 
-u32_t can_mcan_get_core_clock(struct device *dev)
-{
-	u32_t core_clock = LL_RCC_GetFDCANClockFreq(LL_RCC_FDCAN_CLKSOURCE);
-	u32_t dbrp, nbrp;
+#include <logging/log.h>
+LOG_MODULE_DECLARE(can_driver, CONFIG_CAN_LOG_LEVEL);
 
-#if CONFIG_CAN_CKDIV != 0
-	core_clock /= CONFIG_CAN_CKDIV * 2;
+#if CONFIG_CAN_STM32_CLOCK_DIVISOR != 1 && CONFIG_CAN_STM32_CLOCK_DIVISOR & 0x01
+#error CAN_STM32_CLOCK_DIVISOR invalid.\
+Allowed values are 1 or 2 * n, where n <= 15
 #endif
 
-__weak void can_mcan_clock_enable()
+#define DT_DRV_COMPAT st_stm32_fdcan
+
+int can_stm32fd_get_core_clock(const struct device *dev, uint32_t *rate)
+{
+	ARG_UNUSED(dev);
+	int rate_tmp;
+
+	rate_tmp = LL_RCC_GetFDCANClockFreq(LL_RCC_FDCAN_CLKSOURCE);
+
+	if (rate_tmp == LL_RCC_PERIPH_FREQUENCY_NO) {
+		LOG_ERR("Can't read core clock");
+		return -EIO;
+	}
+
+	*rate = rate_tmp / CONFIG_CAN_STM32_CLOCK_DIVISOR;
+
+	return 0;
+}
+
+void can_stm32fd_clock_enable(void)
 {
 	LL_RCC_SetFDCANClockSource(LL_RCC_FDCAN_CLKSOURCE_PCLK1);
 	__HAL_RCC_FDCAN_CLK_ENABLE();
 
-	FDCAN_CONFIG->CKDIV = CONFIG_CAN_CKDIV;
+	FDCAN_CONFIG->CKDIV = CONFIG_CAN_STM32_CLOCK_DIVISOR >> 1;
 }
+
+void can_stm32fd_register_state_change_isr(const struct device *dev,
+					   can_state_change_isr_t isr)
+{
+	struct can_stm32fd_data *data = DEV_DATA(dev);
+
+	data->mcan_data.state_change_isr = isr;
+}
+
+static int can_stm32fd_init(const struct device *dev)
+{
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	const struct can_mcan_config *mcan_cfg = &cfg->mcan_cfg;
+	struct can_mcan_data *mcan_data = &DEV_DATA(dev)->mcan_data;
+	struct can_mcan_msg_sram *msg_ram = cfg->msg_sram;
+	int ret;
+
+	/* Configure dt provided device signals when available */
+	ret = stm32_dt_pinctrl_configure(cfg->pinctrl,
+					 ARRAY_SIZE(cfg->pinctrl),
+					 (uint32_t)mcan_cfg->can);
+	if (ret < 0) {
+		LOG_ERR("CAN pinctrl setup failed (%d)", ret);
+		return ret;
+	}
+
+	can_stm32fd_clock_enable();
+	ret = can_mcan_init(dev, mcan_cfg, msg_ram, mcan_data);
+	if (ret) {
+		return ret;
+	}
+
+	cfg->config_irq();
+
+	return ret;
+}
+
+enum can_state can_stm32fd_get_state(const struct device *dev,
+				     struct can_bus_err_cnt *err_cnt)
+{
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	const struct can_mcan_config *mcan_cfg = &cfg->mcan_cfg;
+
+	return can_mcan_get_state(mcan_cfg, err_cnt);
+}
+
+int can_stm32fd_send(const struct device *dev, const struct zcan_frame *frame,
+		     k_timeout_t timeout, can_tx_callback_t callback,
+		     void *callback_arg)
+{
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	const struct can_mcan_config *mcan_cfg = &cfg->mcan_cfg;
+	struct can_mcan_data *mcan_data = &DEV_DATA(dev)->mcan_data;
+	struct can_mcan_msg_sram *msg_ram = cfg->msg_sram;
+
+	return can_mcan_send(mcan_cfg, mcan_data, msg_ram, frame, timeout,
+			     callback, callback_arg);
+}
+
+int can_stm32fd_attach_isr(const struct device *dev, can_rx_callback_t isr,
+			   void *cb_arg, const struct zcan_filter *filter)
+{
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	struct can_mcan_data *mcan_data = &DEV_DATA(dev)->mcan_data;
+	struct can_mcan_msg_sram *msg_ram = cfg->msg_sram;
+
+	return can_mcan_attach_isr(mcan_data, msg_ram, isr, cb_arg, filter);
+}
+
+void can_stm32fd_detach(const struct device *dev, int filter_nr)
+{
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	struct can_mcan_data *mcan_data = &DEV_DATA(dev)->mcan_data;
+	struct can_mcan_msg_sram *msg_ram = cfg->msg_sram;
+
+	can_mcan_detach(mcan_data, msg_ram, filter_nr);
+}
+
+int can_stm32fd_set_mode(const struct device *dev, enum can_mode mode)
+{
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	const struct can_mcan_config *mcan_cfg = &cfg->mcan_cfg;
+
+	return can_mcan_set_mode(mcan_cfg, mode);
+}
+
+int can_stm32fd_set_timing(const struct device *dev,
+			   const struct can_timing *timing,
+			   const struct can_timing *timing_data)
+{
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	const struct can_mcan_config *mcan_cfg = &cfg->mcan_cfg;
+
+	return can_mcan_set_timing(mcan_cfg, timing, timing_data);
+}
+
+void can_stm32fd_line_0_isr(void *arg)
+{
+	struct device *dev = (struct device *)arg;
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	const struct can_mcan_config *mcan_cfg = &cfg->mcan_cfg;
+	struct can_stm32fd_data *data = DEV_DATA(dev);
+	struct can_mcan_data *mcan_data = &data->mcan_data;
+	struct can_mcan_msg_sram *msg_ram = cfg->msg_sram;
+
+	can_mcan_line_0_isr(mcan_cfg, msg_ram, mcan_data);
+}
+
+void can_stm32fd_line_1_isr(void *arg)
+{
+	struct device *dev = (struct device *)arg;
+	const struct can_stm32fd_config *cfg = DEV_CFG(dev);
+	const struct can_mcan_config *mcan_cfg = &cfg->mcan_cfg;
+	struct can_mcan_data *mcan_data = &DEV_DATA(dev)->mcan_data;
+	struct can_mcan_msg_sram *msg_ram = cfg->msg_sram;
+
+	can_mcan_line_1_isr(mcan_cfg, msg_ram, mcan_data);
+}
+
+static const struct can_driver_api can_api_funcs = {
+	.set_mode = can_stm32fd_set_mode,
+	.set_timing = can_stm32fd_set_timing,
+	.send = can_stm32fd_send,
+	.attach_isr = can_stm32fd_attach_isr,
+	.detach = can_stm32fd_detach,
+	.get_state = can_stm32fd_get_state,
+#ifndef CONFIG_CAN_AUTO_BUS_OFF_RECOVERY
+	.recover = can_mcan_recover,
+#endif
+	.get_core_clock = can_stm32fd_get_core_clock,
+	.register_state_change_isr = can_stm32fd_register_state_change_isr,
+	.timing_min = {
+		.sjw = 0x7f,
+		.prop_seg = 0x00,
+		.phase_seg1 = 0x01,
+		.phase_seg2 = 0x01,
+		.prescaler = 0x01
+	},
+	.timing_max = {
+		.sjw = 0x7f,
+		.prop_seg = 0x00,
+		.phase_seg1 = 0x100,
+		.phase_seg2 = 0x80,
+		.prescaler = 0x200
+	},
+#ifdef CONFIG_CAN_FD_MODE
+	.timing_min_data = {
+		.sjw = 0x01,
+		.prop_seg = 0x01,
+		.phase_seg1 = 0x01,
+		.phase_seg2 = 0x01,
+		.prescaler = 0x01
+	},
+	.timing_max_data = {
+		.sjw = 0x10,
+		.prop_seg = 0x00,
+		.phase_seg1 = 0x20,
+		.phase_seg2 = 0x10,
+		.prescaler = 0x20
+	}
+#endif
+};
+
+#define CAN_STM32FD_IRQ_CFG_FUNCTION(inst)                                     \
+static void config_can_##inst##_irq(void)                                      \
+{                                                                              \
+	LOG_DBG("Enable CAN" #inst " IRQ");                                    \
+	IRQ_CONNECT(DT_INST_IRQ_BY_NAME(inst, line_0, irq),                    \
+		    DT_INST_IRQ_BY_NAME(inst, line_0, priority),               \
+		    can_stm32fd_line_0_isr, DEVICE_DT_INST_GET(inst), 0);      \
+	irq_enable(DT_INST_IRQ_BY_NAME(inst, line_0, irq));                    \
+	IRQ_CONNECT(DT_INST_IRQ_BY_NAME(inst, line_1, irq),                    \
+		    DT_INST_IRQ_BY_NAME(inst, line_1, priority),               \
+		    can_stm32fd_line_1_isr, DEVICE_DT_INST_GET(inst), 0);      \
+	irq_enable(DT_INST_IRQ_BY_NAME(inst, line_1, irq));                    \
+}
+
+#ifdef CONFIG_CAN_FD_MODE
+
+#define CAN_STM32FD_CFG_INST(inst)                                             \
+static const struct can_stm32fd_config can_stm32fd_cfg_##inst = {              \
+	.msg_sram = (struct can_mcan_msg_sram *)                               \
+			DT_INST_REG_ADDR_BY_NAME(inst, message_ram),           \
+	.config_irq = config_can_##inst##_irq,                                 \
+	.mcan_cfg = {                                                          \
+		.can = (struct can_mcan_reg *)                                 \
+			DT_INST_REG_ADDR_BY_NAME(inst, m_can),                 \
+		.bus_speed = DT_INST_PROP(inst, bus_speed),                    \
+		.sjw = DT_INST_PROP(inst, sjw),                                \
+		.sample_point = DT_INST_PROP_OR(inst, sample_point, 0),        \
+		.prop_ts1 = DT_INST_PROP_OR(inst, prop_seg, 0) +               \
+			    DT_INST_PROP_OR(inst, phase_seg1, 0),              \
+		.ts2 = DT_INST_PROP_OR(inst, phase_seg2, 0),                   \
+		.bus_speed_data = DT_INST_PROP(inst, bus_speed_data),          \
+		.sjw_data = DT_INST_PROP(inst, sjw_data),                      \
+		.sample_point_data =                                           \
+			DT_INST_PROP_OR(inst, sample_point_data, 0),           \
+		.prop_ts1_data = DT_INST_PROP_OR(inst, prop_seg_data, 0) +     \
+				DT_INST_PROP_OR(inst, phase_seg1_data, 0),     \
+		.ts2_data = DT_INST_PROP_OR(inst, phase_seg2_data, 0),         \
+		.tx_delay_comp_offset =                                        \
+			DT_INST_PROP(inst, tx_delay_comp_offset)               \
+	},                                                                     \
+	.pinctrl = ST_STM32_DT_INST_PINCTRL(inst, 0),                          \
+};
+
+#else /* CONFIG_CAN_FD_MODE */
+
+#define CAN_STM32FD_CFG_INST(inst)                                             \
+static const struct can_stm32fd_config can_stm32fd_cfg_##inst = {              \
+	.msg_sram = (struct can_mcan_msg_sram *)                               \
+			DT_INST_REG_ADDR_BY_NAME(inst, message_ram),           \
+	.config_irq = config_can_##inst##_irq,                                 \
+	.mcan_cfg = {                                                          \
+		.can = (struct can_mcan_reg *)                                 \
+			DT_INST_REG_ADDR_BY_NAME(inst, m_can),                 \
+		.bus_speed = DT_INST_PROP(inst, bus_speed),                    \
+		.sjw = DT_INST_PROP(inst, sjw),                                \
+		.sample_point = DT_INST_PROP_OR(inst, sample_point, 0),        \
+		.prop_ts1 = DT_INST_PROP_OR(inst, prop_seg, 0) +               \
+			    DT_INST_PROP_OR(inst, phase_seg1, 0),              \
+		.ts2 = DT_INST_PROP_OR(inst, phase_seg2, 0),                   \
+	},                                                                     \
+	.pinctrl = ST_STM32_DT_INST_PINCTRL(inst, 0),                          \
+};
+
+#endif /* CONFIG_CAN_FD_MODE */
+
+#define CAN_STM32FD_DATA_INST(inst) \
+static struct can_stm32fd_data can_stm32fd_dev_data_##inst;
+
+#define CAN_STM32FD_DEVICE_INST(inst)                                          \
+DEVICE_DT_INST_DEFINE(inst, &can_stm32fd_init, NULL,                           \
+		      &can_stm32fd_dev_data_##inst, &can_stm32fd_cfg_##inst,   \
+		      POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEVICE,         \
+		      &can_api_funcs);
+
+#define CAN_STM32FD_INST(inst)     \
+CAN_STM32FD_IRQ_CFG_FUNCTION(inst) \
+CAN_STM32FD_CFG_INST(inst)         \
+CAN_STM32FD_DATA_INST(inst)        \
+CAN_STM32FD_DEVICE_INST(inst)
+
+DT_INST_FOREACH_STATUS_OKAY(CAN_STM32FD_INST)
diff --git a/drivers/can/can_stm32fd.h b/drivers/can/can_stm32fd.h
new file mode 100644
index 0000000..8901899
--- /dev/null
+++ b/drivers/can/can_stm32fd.h
@@ -0,0 +1,29 @@
+/*
+ * Copyright (c) 2020 Alexander Wachter
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ */
+
+#ifndef ZEPHYR_DRIVERS_CAN_STM32FD_H_
+#define ZEPHYR_DRIVERS_CAN_STM32FD_H_
+
+#include "can_mcan.h"
+#include <pinmux/stm32/pinmux_stm32.h>
+
+#define DEV_DATA(dev) ((struct can_stm32fd_data *)(dev)->data)
+#define DEV_CFG(dev) ((const struct can_stm32fd_config *)(dev)->config)
+
+struct can_stm32fd_config {
+	struct can_mcan_msg_sram *msg_sram;
+	void (*config_irq)(void);
+	struct can_mcan_config mcan_cfg;
+	/* CAN always has an RX and TX pin. Hence, hardcode it to two*/
+	const struct soc_gpio_pinctrl pinctrl[2];
+};
+
+struct can_stm32fd_data {
+	struct can_mcan_data mcan_data;
+};
+
+#endif /*ZEPHYR_DRIVERS_CAN_STM32FD_H_*/
diff --git a/dts/bindings/can/st,stm32-fdcan.yaml b/dts/bindings/can/st,stm32-fdcan.yaml
new file mode 100644
index 0000000..8da5e0a
--- /dev/null
+++ b/dts/bindings/can/st,stm32-fdcan.yaml
@@ -0,0 +1,16 @@
+description: Bosch m_can CAN-FD controller
+
+compatible: "st,stm32-fdcan"
+
+include: bosch-mcan.yaml
+
+properties:
+    pinctrl-0:
+      type: phandles
+      required: false
+      description: |
+        GPIO pin configuration for CAN signals (RX, TX). We expect
+        that the phandles will reference pinctrl nodes.
+
+        For example the can1 would be
+           pinctrl-0 = <&fdcan1_rx_pa11 &fdcan1_tx_pa12>;