linux-kernel.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers
@ 2024-12-27  9:57 Ming Yu
  2024-12-27  9:57 ` [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694 Ming Yu
                   ` (6 more replies)
  0 siblings, 7 replies; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

This patch series introduces support for Nuvoton NCT6694, a peripheral
expander based on USB interface. It models the chip as an MFD driver
(1/7), GPIO driver(2/7), I2C Adapter driver(3/7), CANfd driver(4/7),
WDT driver(5/7), HWMON driver(6/7), and RTC driver(7/7).

The MFD driver implements USB device functionality to issue
custom-define USB bulk pipe packets for NCT6694. Each child device can
use the USB functions nct6694_read_msg() and nct6694_write_msg() to issue
a command. They can also request interrupt that will be called when the
USB device receives its interrupt pipe.

The following introduces the custom-define USB transactions:
        nct6694_read_msg - Send bulk-out pipe to write request packet
                           Receive bulk-in pipe to read response packet
                           Receive bulk-in pipe to read data packet

        nct6694_write_msg - Send bulk-out pipe to write request packet
                            Send bulk-out pipe to write data packet
                            Receive bulk-in pipe to read response packet
                            Receive bulk-in pipe to read data packet

Changes since version 3:
- Modify array buffer to structure for each drivers
- Fix defines and comments for each drivers
- Add header <linux/bits.h> and use BIT macro in nct6694.c and
  gpio-nct6694.c
- Modify mutex_init() to devm_mutex_init()
- Add rx-offload helper in nct6694_canfd.c
- Drop watchdog_init_timeout() in nct6694_wdt.c
- Modify the division method to DIV_ROUND_CLOSEST() in nct6694-hwmon.c
- Drop private mutex and use rtc core lock in rtc-nct6694.c
- Modify device_set_wakeup_capable() to device_init_wakeup() in
  rtc-nct6694.c

Changes since version 2:
- Add MODULE_ALIAS() for each child driver
- Modify gpio line names be a local variable in gpio-nct6694.c
- Drop unnecessary platform_get_drvdata() in gpio-nct6694.c
- Rename each command in nct6694_canfd.c
- Modify each function name consistently in nct6694_canfd.c
- Modify the pretimeout validation procedure in nct6694_wdt.c
- Fix warnings in nct6694-hwmon.c

Changes since version 1:
- Implement IRQ domain to handle IRQ demux in nct6694.c
- Modify USB_DEVICE to USB_DEVICE_AND_INTERFACE_INFO API in nct6694.c
- Add each driver's command structure
- Fix USB functions in nct6694.c
- Fix platform driver registration in each child driver
- Sort each driver's header files alphabetically
- Drop unnecessary header in gpio-nct6694.c
- Add gpio line names in gpio-nct6694.c
- Fix errors and warnings in nct6694_canfd.c
- Fix TX-flow control in nct6694_canfd.c
- Fix warnings in nct6694_wdt.c
- Drop unnecessary logs in nct6694_wdt.c
- Modify start() function to setup device in nct6694_wdt.c
- Add voltage sensors functionality in nct6694-hwmon.c
- Add temperature sensors functionality in nct6694-hwmon.c
- Fix overwrite error return values in nct6694-hwmon.c
- Add write value limitation for each write() function in nct6694-hwmon.c
- Drop unnecessary logs in rtc-nct6694.c
- Fix overwrite error return values in rtc-nct6694.c
- Modify to use dev_err_probe API in rtc-nct6694.c


Ming Yu (7):
  mfd: Add core driver for Nuvoton NCT6694
  gpio: Add Nuvoton NCT6694 GPIO support
  i2c: Add Nuvoton NCT6694 I2C support
  can: Add Nuvoton NCT6694 CAN support
  watchdog: Add Nuvoton NCT6694 WDT support
  hwmon: Add Nuvoton NCT6694 HWMON support
  rtc: Add Nuvoton NCT6694 RTC support

 MAINTAINERS                      |  13 +
 drivers/gpio/Kconfig             |  12 +
 drivers/gpio/Makefile            |   1 +
 drivers/gpio/gpio-nct6694.c      | 462 +++++++++++++++++
 drivers/hwmon/Kconfig            |  10 +
 drivers/hwmon/Makefile           |   1 +
 drivers/hwmon/nct6694-hwmon.c    | 851 +++++++++++++++++++++++++++++++
 drivers/i2c/busses/Kconfig       |  10 +
 drivers/i2c/busses/Makefile      |   1 +
 drivers/i2c/busses/i2c-nct6694.c | 156 ++++++
 drivers/mfd/Kconfig              |  10 +
 drivers/mfd/Makefile             |   2 +
 drivers/mfd/nct6694.c            | 394 ++++++++++++++
 drivers/net/can/Kconfig          |  10 +
 drivers/net/can/Makefile         |   1 +
 drivers/net/can/nct6694_canfd.c  | 826 ++++++++++++++++++++++++++++++
 drivers/rtc/Kconfig              |  10 +
 drivers/rtc/Makefile             |   1 +
 drivers/rtc/rtc-nct6694.c        | 263 ++++++++++
 drivers/watchdog/Kconfig         |  11 +
 drivers/watchdog/Makefile        |   1 +
 drivers/watchdog/nct6694_wdt.c   | 281 ++++++++++
 include/linux/mfd/nct6694.h      | 142 ++++++
 23 files changed, 3469 insertions(+)
 create mode 100644 drivers/gpio/gpio-nct6694.c
 create mode 100644 drivers/hwmon/nct6694-hwmon.c
 create mode 100644 drivers/i2c/busses/i2c-nct6694.c
 create mode 100644 drivers/mfd/nct6694.c
 create mode 100644 drivers/net/can/nct6694_canfd.c
 create mode 100644 drivers/rtc/rtc-nct6694.c
 create mode 100644 drivers/watchdog/nct6694_wdt.c
 create mode 100644 include/linux/mfd/nct6694.h

-- 
2.34.1


^ permalink raw reply	[flat|nested] 22+ messages in thread

* [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694
  2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
@ 2024-12-27  9:57 ` Ming Yu
  2024-12-27 15:34   ` Vincent Mailhol
  2024-12-27  9:57 ` [PATCH v4 2/7] gpio: Add Nuvoton NCT6694 GPIO support Ming Yu
                   ` (5 subsequent siblings)
  6 siblings, 1 reply; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

The Nuvoton NCT6694 is a peripheral expander with 16 GPIO chips,
6 I2C controllers, 2 CANfd controllers, 2 Watchdog timers, ADC,
PWM, and RTC.

This driver implements USB device functionality and shares the
chip's peripherals as a child device.

Each child device can use the USB functions nct6694_read_msg()
and nct6694_write_msg() to issue a command. They can also request
interrupt that will be called when the USB device receives its
interrupt pipe.

Signed-off-by: Ming Yu <a0282524688@gmail.com>
---
 MAINTAINERS                 |   7 +
 drivers/mfd/Kconfig         |  10 +
 drivers/mfd/Makefile        |   2 +
 drivers/mfd/nct6694.c       | 394 ++++++++++++++++++++++++++++++++++++
 include/linux/mfd/nct6694.h | 142 +++++++++++++
 5 files changed, 555 insertions(+)
 create mode 100644 drivers/mfd/nct6694.c
 create mode 100644 include/linux/mfd/nct6694.h

diff --git a/MAINTAINERS b/MAINTAINERS
index 910305c11e8a..acb270037642 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -16722,6 +16722,13 @@ F:	drivers/nubus/
 F:	include/linux/nubus.h
 F:	include/uapi/linux/nubus.h
 
+NUVOTON NCT6694 MFD DRIVER
+M:	Ming Yu <tmyu0@nuvoton.com>
+L:	linux-kernel@vger.kernel.org
+S:	Supported
+F:	drivers/mfd/nct6694.c
+F:	include/linux/mfd/nct6694.h
+
 NVIDIA (rivafb and nvidiafb) FRAMEBUFFER DRIVER
 M:	Antonino Daplas <adaplas@gmail.com>
 L:	linux-fbdev@vger.kernel.org
diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
index ae23b317a64e..5429ba97b457 100644
--- a/drivers/mfd/Kconfig
+++ b/drivers/mfd/Kconfig
@@ -558,6 +558,16 @@ config MFD_MX25_TSADC
 	  i.MX25 processors. They consist of a conversion queue for general
 	  purpose ADC and a queue for Touchscreens.
 
+config MFD_NCT6694
+	tristate "Nuvoton NCT6694 support"
+	select MFD_CORE
+	depends on USB
+	help
+	  This adds support for Nuvoton USB device NCT6694 sharing peripherals
+	  This includes the USB devcie driver and core APIs.
+	  Additional drivers must be enabled in order to use the functionality
+	  of the device.
+
 config MFD_HI6421_PMIC
 	tristate "HiSilicon Hi6421 PMU/Codec IC"
 	depends on OF
diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
index e057d6d6faef..9d0365ba6a26 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -117,6 +117,8 @@ obj-$(CONFIG_TWL6040_CORE)	+= twl6040.o
 
 obj-$(CONFIG_MFD_MX25_TSADC)	+= fsl-imx25-tsadc.o
 
+obj-$(CONFIG_MFD_NCT6694)	+= nct6694.o
+
 obj-$(CONFIG_MFD_MC13XXX)	+= mc13xxx-core.o
 obj-$(CONFIG_MFD_MC13XXX_SPI)	+= mc13xxx-spi.o
 obj-$(CONFIG_MFD_MC13XXX_I2C)	+= mc13xxx-i2c.o
diff --git a/drivers/mfd/nct6694.c b/drivers/mfd/nct6694.c
new file mode 100644
index 000000000000..0f31489ef9fa
--- /dev/null
+++ b/drivers/mfd/nct6694.c
@@ -0,0 +1,394 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Nuvoton NCT6694 MFD driver based on USB interface.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#include <linux/bits.h>
+#include <linux/interrupt.h>
+#include <linux/irq.h>
+#include <linux/irqdomain.h>
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/nct6694.h>
+#include <linux/module.h>
+#include <linux/slab.h>
+#include <linux/usb.h>
+
+#define MFD_DEV_SIMPLE(_name)				\
+{							\
+	.name = NCT6694_DEV_##_name,			\
+}							\
+
+#define MFD_DEV_WITH_ID(_name, _id)			\
+{							\
+	.name = NCT6694_DEV_##_name,			\
+	.id = _id,					\
+}
+
+/* MFD device resources */
+static const struct mfd_cell nct6694_dev[] = {
+	MFD_DEV_WITH_ID(GPIO, 0x0),
+	MFD_DEV_WITH_ID(GPIO, 0x1),
+	MFD_DEV_WITH_ID(GPIO, 0x2),
+	MFD_DEV_WITH_ID(GPIO, 0x3),
+	MFD_DEV_WITH_ID(GPIO, 0x4),
+	MFD_DEV_WITH_ID(GPIO, 0x5),
+	MFD_DEV_WITH_ID(GPIO, 0x6),
+	MFD_DEV_WITH_ID(GPIO, 0x7),
+	MFD_DEV_WITH_ID(GPIO, 0x8),
+	MFD_DEV_WITH_ID(GPIO, 0x9),
+	MFD_DEV_WITH_ID(GPIO, 0xA),
+	MFD_DEV_WITH_ID(GPIO, 0xB),
+	MFD_DEV_WITH_ID(GPIO, 0xC),
+	MFD_DEV_WITH_ID(GPIO, 0xD),
+	MFD_DEV_WITH_ID(GPIO, 0xE),
+	MFD_DEV_WITH_ID(GPIO, 0xF),
+
+	MFD_DEV_WITH_ID(I2C, 0x0),
+	MFD_DEV_WITH_ID(I2C, 0x1),
+	MFD_DEV_WITH_ID(I2C, 0x2),
+	MFD_DEV_WITH_ID(I2C, 0x3),
+	MFD_DEV_WITH_ID(I2C, 0x4),
+	MFD_DEV_WITH_ID(I2C, 0x5),
+
+	MFD_DEV_WITH_ID(CAN, 0x0),
+	MFD_DEV_WITH_ID(CAN, 0x1),
+
+	MFD_DEV_WITH_ID(WDT, 0x0),
+	MFD_DEV_WITH_ID(WDT, 0x1),
+
+	MFD_DEV_SIMPLE(HWMON),
+	MFD_DEV_SIMPLE(RTC),
+};
+
+static int nct6694_response_err_handling(struct nct6694 *nct6694,
+					 unsigned char err_status)
+{
+	struct device *dev = &nct6694->udev->dev;
+
+	switch (err_status) {
+	case NCT6694_NO_ERROR:
+		return err_status;
+	case NCT6694_NOT_SUPPORT_ERROR:
+		dev_dbg(dev, "%s: Command is not support!\n", __func__);
+		break;
+	case NCT6694_NO_RESPONSE_ERROR:
+		dev_dbg(dev, "%s: Command is no response!\n", __func__);
+		break;
+	case NCT6694_TIMEOUT_ERROR:
+		dev_dbg(dev, "%s: Command is timeout!\n", __func__);
+		break;
+	case NCT6694_PENDING:
+		dev_dbg(dev, "%s: Command is pending!\n", __func__);
+		break;
+	default:
+		return -EINVAL;
+	}
+
+	return -EIO;
+}
+
+int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
+		     u16 length, void *buf)
+{
+	union nct6694_usb_msg *msg = nct6694->usb_msg;
+	int tx_len, rx_len, ret;
+
+	guard(mutex)(&nct6694->access_lock);
+
+	memset(msg, 0, sizeof(*msg));
+
+	/* Send command packet to USB device */
+	msg->cmd_header.mod = mod;
+	msg->cmd_header.cmd = offset & 0xFF;
+	msg->cmd_header.sel = (offset >> 8) & 0xFF;
+	msg->cmd_header.hctrl = NCT6694_HCTRL_GET;
+	msg->cmd_header.len = cpu_to_le16(length);
+
+	ret = usb_bulk_msg(nct6694->udev,
+			   usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
+			   &msg->cmd_header, sizeof(*msg), &tx_len,
+			   nct6694->timeout);
+	if (ret)
+		return ret;
+
+	/* Receive response packet from USB device */
+	ret = usb_bulk_msg(nct6694->udev,
+			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
+			   &msg->response_header, sizeof(*msg), &rx_len,
+			   nct6694->timeout);
+	if (ret)
+		return ret;
+
+	/* Receive data packet from USB device */
+	ret = usb_bulk_msg(nct6694->udev,
+			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
+			   buf, NCT6694_MAX_PACKET_SZ, &rx_len, nct6694->timeout);
+	if (ret)
+		return ret;
+
+	if (rx_len != length) {
+		dev_dbg(&nct6694->udev->dev, "%s: Received length is not match!\n",
+			__func__);
+		return -EIO;
+	}
+
+	return nct6694_response_err_handling(nct6694, msg->response_header.sts);
+}
+EXPORT_SYMBOL(nct6694_read_msg);
+
+int nct6694_write_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
+		      u16 length, void *buf)
+{
+	union nct6694_usb_msg *msg = nct6694->usb_msg;
+	int tx_len, rx_len, ret;
+
+	guard(mutex)(&nct6694->access_lock);
+
+	memset(msg, 0, sizeof(*msg));
+
+	/* Send command packet to USB device */
+	msg->cmd_header.mod = mod;
+	msg->cmd_header.cmd = offset & 0xFF;
+	msg->cmd_header.sel = (offset >> 8) & 0xFF;
+	msg->cmd_header.hctrl = NCT6694_HCTRL_SET;
+	msg->cmd_header.len = cpu_to_le16(length);
+
+	ret = usb_bulk_msg(nct6694->udev,
+			   usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
+			   &msg->cmd_header, sizeof(*msg), &tx_len,
+			   nct6694->timeout);
+	if (ret)
+		return ret;
+
+	/* Send data packet to USB device */
+	ret = usb_bulk_msg(nct6694->udev,
+			   usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
+			   buf, length, &tx_len, nct6694->timeout);
+	if (ret)
+		return ret;
+
+	/* Receive response packet from USB device */
+	ret = usb_bulk_msg(nct6694->udev,
+			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
+			   &msg->response_header, sizeof(*msg), &rx_len,
+			   nct6694->timeout);
+	if (ret)
+		return ret;
+
+	/* Receive data packet from USB device */
+	ret = usb_bulk_msg(nct6694->udev,
+			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
+			   buf, NCT6694_MAX_PACKET_SZ, &rx_len, nct6694->timeout);
+	if (ret)
+		return ret;
+
+	if (rx_len != length) {
+		dev_dbg(&nct6694->udev->dev, "%s: Sent length is not match!\n",
+			__func__);
+		return -EIO;
+	}
+
+	return nct6694_response_err_handling(nct6694, msg->response_header.sts);
+}
+EXPORT_SYMBOL(nct6694_write_msg);
+
+static void usb_int_callback(struct urb *urb)
+{
+	struct nct6694 *nct6694 = urb->context;
+	struct device *dev = &nct6694->udev->dev;
+	unsigned int *int_status = urb->transfer_buffer;
+	int ret;
+
+	switch (urb->status) {
+	case 0:
+		break;
+	case -ECONNRESET:
+	case -ENOENT:
+	case -ESHUTDOWN:
+		return;
+	default:
+		goto resubmit;
+	}
+
+	while (*int_status) {
+		int irq = __ffs(*int_status);
+
+		generic_handle_irq_safe(irq_find_mapping(nct6694->domain, irq));
+		*int_status &= ~BIT(irq);
+	}
+
+resubmit:
+	ret = usb_submit_urb(urb, GFP_ATOMIC);
+	if (ret)
+		dev_dbg(dev, "%s: Failed to resubmit urb, status %d",
+			__func__, ret);
+}
+
+static void nct6694_irq_lock(struct irq_data *data)
+{
+	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
+
+	mutex_lock(&nct6694->irq_lock);
+}
+
+static void nct6694_irq_sync_unlock(struct irq_data *data)
+{
+	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
+
+	mutex_unlock(&nct6694->irq_lock);
+}
+
+static void nct6694_irq_enable(struct irq_data *data)
+{
+	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
+	irq_hw_number_t hwirq = irqd_to_hwirq(data);
+
+	nct6694->irq_enable |= BIT(hwirq);
+}
+
+static void nct6694_irq_disable(struct irq_data *data)
+{
+	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
+	irq_hw_number_t hwirq = irqd_to_hwirq(data);
+
+	nct6694->irq_enable &= ~BIT(hwirq);
+}
+
+static struct irq_chip nct6694_irq_chip = {
+	.name = "nct6694-irq",
+	.flags = IRQCHIP_SKIP_SET_WAKE,
+	.irq_bus_lock = nct6694_irq_lock,
+	.irq_bus_sync_unlock = nct6694_irq_sync_unlock,
+	.irq_enable = nct6694_irq_enable,
+	.irq_disable = nct6694_irq_disable,
+};
+
+static int nct6694_irq_domain_map(struct irq_domain *d, unsigned int irq,
+				  irq_hw_number_t hw)
+{
+	struct nct6694 *nct6694 = d->host_data;
+
+	irq_set_chip_data(irq, nct6694);
+	irq_set_chip_and_handler(irq, &nct6694_irq_chip, handle_simple_irq);
+
+	return 0;
+}
+
+static void nct6694_irq_domain_unmap(struct irq_domain *d, unsigned int irq)
+{
+	irq_set_chip_and_handler(irq, NULL, NULL);
+	irq_set_chip_data(irq, NULL);
+}
+
+static const struct irq_domain_ops nct6694_irq_domain_ops = {
+	.map	= nct6694_irq_domain_map,
+	.unmap	= nct6694_irq_domain_unmap,
+};
+
+static int nct6694_usb_probe(struct usb_interface *iface,
+			     const struct usb_device_id *id)
+{
+	struct usb_device *udev = interface_to_usbdev(iface);
+	struct usb_endpoint_descriptor *int_endpoint;
+	struct usb_host_interface *interface;
+	struct device *dev = &udev->dev;
+	struct nct6694 *nct6694;
+	int pipe, maxp;
+	int ret;
+
+	interface = iface->cur_altsetting;
+
+	int_endpoint = &interface->endpoint[0].desc;
+	if (!usb_endpoint_is_int_in(int_endpoint))
+		return -ENODEV;
+
+	nct6694 = devm_kzalloc(dev, sizeof(*nct6694), GFP_KERNEL);
+	if (!nct6694)
+		return -ENOMEM;
+
+	pipe = usb_rcvintpipe(udev, NCT6694_INT_IN_EP);
+	maxp = usb_maxpacket(udev, pipe);
+
+	nct6694->usb_msg = devm_kzalloc(dev, sizeof(union nct6694_usb_msg),
+					GFP_KERNEL);
+	if (!nct6694->usb_msg)
+		return -ENOMEM;
+
+	nct6694->int_buffer = devm_kzalloc(dev, maxp, GFP_KERNEL);
+	if (!nct6694->int_buffer)
+		return -ENOMEM;
+
+	nct6694->int_in_urb = usb_alloc_urb(0, GFP_KERNEL);
+	if (!nct6694->int_in_urb)
+		return -ENOMEM;
+
+	nct6694->domain = irq_domain_add_simple(NULL, NCT6694_NR_IRQS, 0,
+						&nct6694_irq_domain_ops,
+						nct6694);
+	if (!nct6694->domain) {
+		ret = -ENODEV;
+		goto err_urb;
+	}
+
+	nct6694->udev = udev;
+	nct6694->timeout = NCT6694_URB_TIMEOUT;	/* Wait until urb complete */
+
+	devm_mutex_init(dev, &nct6694->access_lock);
+	devm_mutex_init(dev, &nct6694->irq_lock);
+
+	usb_fill_int_urb(nct6694->int_in_urb, udev, pipe,
+			 nct6694->int_buffer, maxp, usb_int_callback,
+			 nct6694, int_endpoint->bInterval);
+	ret = usb_submit_urb(nct6694->int_in_urb, GFP_KERNEL);
+	if (ret)
+		goto err_urb;
+
+	dev_set_drvdata(dev, nct6694);
+	usb_set_intfdata(iface, nct6694);
+
+	ret = mfd_add_hotplug_devices(dev, nct6694_dev, ARRAY_SIZE(nct6694_dev));
+	if (ret)
+		goto err_mfd;
+
+	return 0;
+
+err_mfd:
+	usb_kill_urb(nct6694->int_in_urb);
+err_urb:
+	usb_free_urb(nct6694->int_in_urb);
+	return ret;
+}
+
+static void nct6694_usb_disconnect(struct usb_interface *iface)
+{
+	struct usb_device *udev = interface_to_usbdev(iface);
+	struct nct6694 *nct6694 = usb_get_intfdata(iface);
+
+	mfd_remove_devices(&udev->dev);
+	usb_kill_urb(nct6694->int_in_urb);
+	usb_free_urb(nct6694->int_in_urb);
+}
+
+static const struct usb_device_id nct6694_ids[] = {
+	{ USB_DEVICE_AND_INTERFACE_INFO(NCT6694_VENDOR_ID,
+					NCT6694_PRODUCT_ID,
+					0xFF, 0x00, 0x00)},
+	{}
+};
+MODULE_DEVICE_TABLE(usb, nct6694_ids);
+
+static struct usb_driver nct6694_usb_driver = {
+	.name	= "nct6694",
+	.id_table = nct6694_ids,
+	.probe = nct6694_usb_probe,
+	.disconnect = nct6694_usb_disconnect,
+};
+
+module_usb_driver(nct6694_usb_driver);
+
+MODULE_DESCRIPTION("USB-MFD driver for NCT6694");
+MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
+MODULE_LICENSE("GPL");
diff --git a/include/linux/mfd/nct6694.h b/include/linux/mfd/nct6694.h
new file mode 100644
index 000000000000..38c8c7af10d5
--- /dev/null
+++ b/include/linux/mfd/nct6694.h
@@ -0,0 +1,142 @@
+/* SPDX-License-Identifier: GPL-2.0 */
+/*
+ * Nuvoton NCT6694 USB transaction and data structure.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#ifndef __MFD_NCT6694_H
+#define __MFD_NCT6694_H
+
+#define NCT6694_DEV_GPIO	"nct6694-gpio"
+#define NCT6694_DEV_I2C		"nct6694-i2c"
+#define NCT6694_DEV_CAN		"nct6694-can"
+#define NCT6694_DEV_WDT		"nct6694-wdt"
+#define NCT6694_DEV_HWMON	"nct6694-hwmon"
+#define NCT6694_DEV_RTC		"nct6694-rtc"
+
+#define NCT6694_VENDOR_ID	0x0416
+#define NCT6694_PRODUCT_ID	0x200B
+#define NCT6694_INT_IN_EP	0x81
+#define NCT6694_BULK_IN_EP	0x02
+#define NCT6694_BULK_OUT_EP	0x03
+#define NCT6694_MAX_PACKET_SZ	512
+
+#define NCT6694_HCTRL_SET	0x40
+#define NCT6694_HCTRL_GET	0x80
+
+#define NCT6694_URB_TIMEOUT	1000
+
+enum nct6694_irq_id {
+	NCT6694_IRQ_GPIO0 = 0,
+	NCT6694_IRQ_GPIO1,
+	NCT6694_IRQ_GPIO2,
+	NCT6694_IRQ_GPIO3,
+	NCT6694_IRQ_GPIO4,
+	NCT6694_IRQ_GPIO5,
+	NCT6694_IRQ_GPIO6,
+	NCT6694_IRQ_GPIO7,
+	NCT6694_IRQ_GPIO8,
+	NCT6694_IRQ_GPIO9,
+	NCT6694_IRQ_GPIOA,
+	NCT6694_IRQ_GPIOB,
+	NCT6694_IRQ_GPIOC,
+	NCT6694_IRQ_GPIOD,
+	NCT6694_IRQ_GPIOE,
+	NCT6694_IRQ_GPIOF,
+	NCT6694_IRQ_CAN1,
+	NCT6694_IRQ_CAN2,
+	NCT6694_IRQ_RTC,
+	NCT6694_NR_IRQS,
+};
+
+enum nct6694_response_err_status {
+	NCT6694_NO_ERROR = 0,
+	NCT6694_FORMAT_ERROR,
+	NCT6694_RESERVED1,
+	NCT6694_RESERVED2,
+	NCT6694_NOT_SUPPORT_ERROR,
+	NCT6694_NO_RESPONSE_ERROR,
+	NCT6694_TIMEOUT_ERROR,
+	NCT6694_PENDING,
+};
+
+struct nct6694_cmd_header {
+	u8 rsv1;
+	u8 mod;
+	u8 cmd;
+	u8 sel;
+	u8 hctrl;
+	u8 rsv2;
+	__le16 len;
+} __packed;
+
+struct nct6694_response_header {
+	u8 sequence_id;
+	u8 sts;
+	u8 reserved[4];
+	__le16 len;
+} __packed;
+
+union nct6694_usb_msg {
+	struct nct6694_cmd_header cmd_header;
+	struct nct6694_response_header response_header;
+};
+
+struct nct6694 {
+	struct usb_device *udev;
+	struct urb *int_in_urb;
+	struct irq_domain *domain;
+	struct mutex access_lock;
+	struct mutex irq_lock;
+	union nct6694_usb_msg *usb_msg;
+	unsigned char *int_buffer;
+	unsigned int irq_enable;
+	/* time in msec to wait for the urb to the complete */
+	long timeout;
+};
+
+/*
+ * nct6694_read_msg - Receive data from NCT6694 USB device
+ *
+ * @nct6694 - Nuvoton NCT6694 structure
+ * @mod - Module byte
+ * @offset - Offset byte or (Select byte | Command byte)
+ * @length - Length byte
+ * @buf - Read data from rx buffer
+ *
+ * USB Transaction format:
+ *
+ *	OUT	|RSV|MOD|CMD|SEL|HCTL|RSV|LEN_L|LEN_H|
+ *	OUT	|SEQ|STS|RSV|RSV|RSV|RSV||LEN_L|LEN_H|
+ *	IN	|-------D------A------D------A-------|
+ *	IN			......
+ *	IN	|-------D------A------D------A-------|
+ */
+int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
+		     u16 length, void *buf);
+
+/*
+ * nct6694_read_msg - Transmit data to NCT6694 USB device
+ *
+ * @nct6694 - Nuvoton NCT6694 structure
+ * @mod - Module byte
+ * @offset - Offset byte or (Select byte | Command byte)
+ * @length - Length byte
+ * @buf - Write data to tx buffer
+ *
+ * USB Transaction format:
+ *
+ *	OUT	|RSV|MOD|CMD|SEL|HCTL|RSV|LEN_L|LEN_H|
+ *	OUT	|-------D------A------D------A-------|
+ *	OUT			......
+ *	OUT	|-------D------A------D------A-------|
+ *	IN	|SEQ|STS|RSV|RSV|RSV|RSV||LEN_L|LEN_H|
+ *	IN	|-------D------A------D------A-------|
+ *	IN			......
+ *	IN	|-------D------A------D------A-------|
+ */
+int nct6694_write_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
+		      u16 length, void *buf);
+
+#endif
-- 
2.34.1


^ permalink raw reply related	[flat|nested] 22+ messages in thread

* [PATCH v4 2/7] gpio: Add Nuvoton NCT6694 GPIO support
  2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
  2024-12-27  9:57 ` [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694 Ming Yu
@ 2024-12-27  9:57 ` Ming Yu
  2025-01-13 14:27   ` Linus Walleij
  2024-12-27  9:57 ` [PATCH v4 3/7] i2c: Add Nuvoton NCT6694 I2C support Ming Yu
                   ` (4 subsequent siblings)
  6 siblings, 1 reply; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

This driver supports GPIO and IRQ functionality for NCT6694 MFD
device based on USB interface.

Signed-off-by: Ming Yu <a0282524688@gmail.com>
---
 MAINTAINERS                 |   1 +
 drivers/gpio/Kconfig        |  12 +
 drivers/gpio/Makefile       |   1 +
 drivers/gpio/gpio-nct6694.c | 462 ++++++++++++++++++++++++++++++++++++
 4 files changed, 476 insertions(+)
 create mode 100644 drivers/gpio/gpio-nct6694.c

diff --git a/MAINTAINERS b/MAINTAINERS
index acb270037642..18bf57f47792 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -16726,6 +16726,7 @@ NUVOTON NCT6694 MFD DRIVER
 M:	Ming Yu <tmyu0@nuvoton.com>
 L:	linux-kernel@vger.kernel.org
 S:	Supported
+F:	drivers/gpio/gpio-nct6694.c
 F:	drivers/mfd/nct6694.c
 F:	include/linux/mfd/nct6694.h
 
diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index 93ee3aa092f8..808fbfdbff3b 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -1461,6 +1461,18 @@ config GPIO_MAX77650
 	  GPIO driver for MAX77650/77651 PMIC from Maxim Semiconductor.
 	  These chips have a single pin that can be configured as GPIO.
 
+config GPIO_NCT6694
+	tristate "Nuvoton NCT6694 GPIO controller support"
+	depends on MFD_NCT6694
+	select GENERIC_IRQ_CHIP
+	select GPIOLIB_IRQCHIP
+	help
+	  This driver supports 8 GPIO pins per bank that can all be interrupt
+	  sources.
+
+	  This driver can also be built as a module. If so, the module will be
+	  called gpio-nct6694.
+
 config GPIO_PALMAS
 	bool "TI PALMAS series PMICs GPIO"
 	depends on MFD_PALMAS
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index af3ba4d81b58..ad80a078b27b 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -123,6 +123,7 @@ obj-$(CONFIG_GPIO_MXC)			+= gpio-mxc.o
 obj-$(CONFIG_GPIO_MXS)			+= gpio-mxs.o
 obj-$(CONFIG_GPIO_NOMADIK)		+= gpio-nomadik.o
 obj-$(CONFIG_GPIO_NPCM_SGPIO)		+= gpio-npcm-sgpio.o
+obj-$(CONFIG_GPIO_NCT6694)		+= gpio-nct6694.o
 obj-$(CONFIG_GPIO_OCTEON)		+= gpio-octeon.o
 obj-$(CONFIG_GPIO_OMAP)			+= gpio-omap.o
 obj-$(CONFIG_GPIO_PALMAS)		+= gpio-palmas.o
diff --git a/drivers/gpio/gpio-nct6694.c b/drivers/gpio/gpio-nct6694.c
new file mode 100644
index 000000000000..14c8acfcf5c3
--- /dev/null
+++ b/drivers/gpio/gpio-nct6694.c
@@ -0,0 +1,462 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Nuvoton NCT6694 GPIO controller driver based on USB interface.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#include <linux/bits.h>
+#include <linux/gpio/driver.h>
+#include <linux/interrupt.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/nct6694.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+
+/*
+ * USB command module type for NCT6694 GPIO controller.
+ * This defines the module type used for communication with the NCT6694
+ * GPIO controller over the USB interface.
+ */
+#define NCT6694_GPIO_MOD	0xFF
+
+#define NCT6694_GPIO_VER	0x90
+#define NCT6694_GPIO_VALID	0x110
+#define NCT6694_GPI_DATA	0x120
+#define NCT6694_GPO_DIR		0x170
+#define NCT6694_GPO_TYPE	0x180
+#define NCT6694_GPO_DATA	0x190
+
+#define NCT6694_GPI_STS		0x130
+#define NCT6694_GPI_CLR		0x140
+#define NCT6694_GPI_FALLING	0x150
+#define NCT6694_GPI_RISING	0x160
+
+#define NCT6694_NR_GPIO		8
+
+struct nct6694_gpio_data {
+	struct nct6694 *nct6694;
+	struct gpio_chip gpio;
+	struct mutex lock;
+	/* Protect irq operation */
+	struct mutex irq_lock;
+
+	unsigned char reg_val;
+	unsigned char irq_trig_falling;
+	unsigned char irq_trig_rising;
+
+	/* Current gpio group */
+	unsigned char group;
+};
+
+static int nct6694_get_direction(struct gpio_chip *gpio, unsigned int offset)
+{
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPO_DIR + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	return !(BIT(offset) & data->reg_val);
+}
+
+static int nct6694_direction_input(struct gpio_chip *gpio, unsigned int offset)
+{
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPO_DIR + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	data->reg_val &= ~BIT(offset);
+
+	return nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+				 NCT6694_GPO_DIR + data->group,
+				 sizeof(data->reg_val),
+				 &data->reg_val);
+}
+
+static int nct6694_direction_output(struct gpio_chip *gpio,
+				    unsigned int offset, int val)
+{
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	/* Set direction to output */
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPO_DIR + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	data->reg_val |= BIT(offset);
+	ret = nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+				NCT6694_GPO_DIR + data->group,
+				sizeof(data->reg_val),
+				&data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	/* Then set output level */
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPO_DATA + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	if (val)
+		data->reg_val |= BIT(offset);
+	else
+		data->reg_val &= ~BIT(offset);
+
+	return nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+				 NCT6694_GPO_DATA + data->group,
+				 sizeof(data->reg_val),
+				 &data->reg_val);
+}
+
+static int nct6694_get_value(struct gpio_chip *gpio, unsigned int offset)
+{
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPO_DIR + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	if (BIT(offset) & data->reg_val) {
+		ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+				       NCT6694_GPO_DATA + data->group,
+				       sizeof(data->reg_val),
+				       &data->reg_val);
+		if (ret < 0)
+			return ret;
+
+		return !!(BIT(offset) & data->reg_val);
+	}
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPI_DATA + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	return !!(BIT(offset) & data->reg_val);
+}
+
+static void nct6694_set_value(struct gpio_chip *gpio, unsigned int offset,
+			      int val)
+{
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+
+	guard(mutex)(&data->lock);
+
+	nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			 NCT6694_GPO_DATA + data->group,
+			 sizeof(data->reg_val),
+			 &data->reg_val);
+
+	if (val)
+		data->reg_val |= BIT(offset);
+	else
+		data->reg_val &= ~BIT(offset);
+
+	nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+			  NCT6694_GPO_DATA + data->group,
+			  sizeof(data->reg_val),
+			  &data->reg_val);
+}
+
+static int nct6694_set_config(struct gpio_chip *gpio, unsigned int offset,
+			      unsigned long config)
+{
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPO_TYPE + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	switch (pinconf_to_config_param(config)) {
+	case PIN_CONFIG_DRIVE_OPEN_DRAIN:
+		data->reg_val |= BIT(offset);
+		break;
+	case PIN_CONFIG_DRIVE_PUSH_PULL:
+		data->reg_val &= ~BIT(offset);
+		break;
+	default:
+		return -ENOTSUPP;
+	}
+
+	return nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+				 NCT6694_GPO_TYPE + data->group,
+				 sizeof(data->reg_val),
+				 &data->reg_val);
+}
+
+static int nct6694_init_valid_mask(struct gpio_chip *gpio,
+				   unsigned long *valid_mask,
+				   unsigned int ngpios)
+{
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPIO_VALID + data->group,
+			       sizeof(data->reg_val),
+			       &data->reg_val);
+	if (ret < 0)
+		return ret;
+
+	*valid_mask = data->reg_val;
+
+	return ret;
+}
+
+static irqreturn_t nct6694_irq_handler(int irq, void *priv)
+{
+	struct nct6694_gpio_data *data = priv;
+	unsigned char status;
+
+	guard(mutex)(&data->lock);
+
+	nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			 NCT6694_GPI_STS + data->group,
+			 sizeof(data->reg_val),
+			 &data->reg_val);
+
+	status = data->reg_val;
+
+	while (status) {
+		int bit = __ffs(status);
+
+		data->reg_val = BIT(bit);
+		handle_nested_irq(irq_find_mapping(data->gpio.irq.domain, bit));
+		status &= ~BIT(bit);
+		nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+				  NCT6694_GPI_CLR + data->group,
+				  sizeof(data->reg_val),
+				  &data->reg_val);
+	}
+
+	return IRQ_HANDLED;
+}
+
+static int nct6694_get_irq_trig(struct nct6694_gpio_data *data)
+{
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+			       NCT6694_GPI_FALLING + data->group,
+			       sizeof(data->irq_trig_falling),
+			       &data->irq_trig_falling);
+	if (ret)
+		return ret;
+
+	return nct6694_read_msg(data->nct6694, NCT6694_GPIO_MOD,
+				NCT6694_GPI_RISING + data->group,
+				sizeof(data->irq_trig_rising),
+				&data->irq_trig_rising);
+}
+
+static void nct6694_irq_mask(struct irq_data *d)
+{
+	struct gpio_chip *gpio = irq_data_get_irq_chip_data(d);
+	irq_hw_number_t hwirq = irqd_to_hwirq(d);
+
+	gpiochip_disable_irq(gpio, hwirq);
+}
+
+static void nct6694_irq_unmask(struct irq_data *d)
+{
+	struct gpio_chip *gpio = irq_data_get_irq_chip_data(d);
+	irq_hw_number_t hwirq = irqd_to_hwirq(d);
+
+	gpiochip_enable_irq(gpio, hwirq);
+}
+
+static int nct6694_irq_set_type(struct irq_data *d, unsigned int type)
+{
+	struct gpio_chip *gpio = irq_data_get_irq_chip_data(d);
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+	irq_hw_number_t hwirq = irqd_to_hwirq(d);
+
+	guard(mutex)(&data->lock);
+
+	switch (type) {
+	case IRQ_TYPE_EDGE_RISING:
+		data->irq_trig_rising |= BIT(hwirq);
+		break;
+
+	case IRQ_TYPE_EDGE_FALLING:
+		data->irq_trig_falling |= BIT(hwirq);
+		break;
+
+	case IRQ_TYPE_EDGE_BOTH:
+		data->irq_trig_rising |= BIT(hwirq);
+		data->irq_trig_falling |= BIT(hwirq);
+		break;
+
+	default:
+		return -ENOTSUPP;
+	}
+
+	return 0;
+}
+
+static void nct6694_irq_bus_lock(struct irq_data *d)
+{
+	struct gpio_chip *gpio = irq_data_get_irq_chip_data(d);
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+
+	mutex_lock(&data->irq_lock);
+}
+
+static void nct6694_irq_bus_sync_unlock(struct irq_data *d)
+{
+	struct gpio_chip *gpio = irq_data_get_irq_chip_data(d);
+	struct nct6694_gpio_data *data = gpiochip_get_data(gpio);
+
+	scoped_guard(mutex, &data->lock) {
+		nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+				  NCT6694_GPI_FALLING + data->group,
+				  sizeof(data->irq_trig_falling),
+				  &data->irq_trig_falling);
+
+		nct6694_write_msg(data->nct6694, NCT6694_GPIO_MOD,
+				  NCT6694_GPI_RISING + data->group,
+				  sizeof(data->irq_trig_rising),
+				  &data->irq_trig_rising);
+	}
+
+	mutex_unlock(&data->irq_lock);
+}
+
+static const struct irq_chip nct6694_irq_chip = {
+	.name			= "nct6694-gpio",
+	.irq_mask		= nct6694_irq_mask,
+	.irq_unmask		= nct6694_irq_unmask,
+	.irq_set_type		= nct6694_irq_set_type,
+	.irq_bus_lock		= nct6694_irq_bus_lock,
+	.irq_bus_sync_unlock	= nct6694_irq_bus_sync_unlock,
+	.flags			= IRQCHIP_IMMUTABLE,
+	GPIOCHIP_IRQ_RESOURCE_HELPERS,
+};
+
+static int nct6694_gpio_probe(struct platform_device *pdev)
+{
+	const struct mfd_cell *cell = mfd_get_cell(pdev);
+	struct device *dev = &pdev->dev;
+	struct nct6694 *nct6694 = dev_get_drvdata(pdev->dev.parent);
+	struct nct6694_gpio_data *data;
+	struct gpio_irq_chip *girq;
+	int ret, irq, i;
+	char **names;
+
+	irq = irq_create_mapping(nct6694->domain,
+				 NCT6694_IRQ_GPIO0 + cell->id);
+	if (!irq)
+		return -EINVAL;
+
+	data = devm_kzalloc(dev, sizeof(*data), GFP_KERNEL);
+	if (!data)
+		return -ENOMEM;
+
+	names = devm_kcalloc(dev, NCT6694_NR_GPIO, sizeof(char *),
+			     GFP_KERNEL);
+	if (!names)
+		return -ENOMEM;
+
+	for (i = 0; i < NCT6694_NR_GPIO; i++) {
+		names[i] = devm_kasprintf(dev, GFP_KERNEL, "GPIO%X%d",
+					  cell->id, i);
+		if (!names[i])
+			return -ENOMEM;
+	}
+
+	data->nct6694 = nct6694;
+	data->group = cell->id;
+
+	data->gpio.names		= (const char * const*)names;
+	data->gpio.label		= pdev->name;
+	data->gpio.direction_input	= nct6694_direction_input;
+	data->gpio.get			= nct6694_get_value;
+	data->gpio.direction_output	= nct6694_direction_output;
+	data->gpio.set			= nct6694_set_value;
+	data->gpio.get_direction	= nct6694_get_direction;
+	data->gpio.set_config		= nct6694_set_config;
+	data->gpio.init_valid_mask	= nct6694_init_valid_mask;
+	data->gpio.base			= -1;
+	data->gpio.can_sleep		= false;
+	data->gpio.owner		= THIS_MODULE;
+	data->gpio.ngpio		= NCT6694_NR_GPIO;
+
+	devm_mutex_init(dev, &data->lock);
+	devm_mutex_init(dev, &data->irq_lock);
+
+	ret = nct6694_get_irq_trig(data);
+	if (ret)
+		return dev_err_probe(dev, ret, "Failed to get irq trigger type\n");
+
+	girq = &data->gpio.irq;
+	gpio_irq_chip_set_chip(girq, &nct6694_irq_chip);
+	girq->parent_handler = NULL;
+	girq->num_parents = 0;
+	girq->parents = NULL;
+	girq->default_type = IRQ_TYPE_NONE;
+	girq->handler = handle_level_irq;
+	girq->threaded = true;
+
+	ret = devm_request_threaded_irq(dev, irq, NULL, nct6694_irq_handler,
+					IRQF_ONESHOT | IRQF_SHARED,
+					"nct6694-gpio", data);
+	if (ret)
+		return dev_err_probe(dev, ret, "Failed to request irq\n");
+
+	return devm_gpiochip_add_data(dev, &data->gpio, data);
+}
+
+static struct platform_driver nct6694_gpio_driver = {
+	.driver = {
+		.name	= "nct6694-gpio",
+	},
+	.probe		= nct6694_gpio_probe,
+};
+
+module_platform_driver(nct6694_gpio_driver);
+
+MODULE_DESCRIPTION("USB-GPIO controller driver for NCT6694");
+MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:nct6694-gpio");
-- 
2.34.1


^ permalink raw reply related	[flat|nested] 22+ messages in thread

* [PATCH v4 3/7] i2c: Add Nuvoton NCT6694 I2C support
  2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
  2024-12-27  9:57 ` [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694 Ming Yu
  2024-12-27  9:57 ` [PATCH v4 2/7] gpio: Add Nuvoton NCT6694 GPIO support Ming Yu
@ 2024-12-27  9:57 ` Ming Yu
  2024-12-27  9:57 ` [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support Ming Yu
                   ` (3 subsequent siblings)
  6 siblings, 0 replies; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

This driver supports I2C adapter functionality for NCT6694 MFD
device based on USB interface, each I2C controller use default
baudrate(100K).

Signed-off-by: Ming Yu <a0282524688@gmail.com>
---
 MAINTAINERS                      |   1 +
 drivers/i2c/busses/Kconfig       |  10 ++
 drivers/i2c/busses/Makefile      |   1 +
 drivers/i2c/busses/i2c-nct6694.c | 156 +++++++++++++++++++++++++++++++
 4 files changed, 168 insertions(+)
 create mode 100644 drivers/i2c/busses/i2c-nct6694.c

diff --git a/MAINTAINERS b/MAINTAINERS
index 18bf57f47792..5d63542233c4 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -16727,6 +16727,7 @@ M:	Ming Yu <tmyu0@nuvoton.com>
 L:	linux-kernel@vger.kernel.org
 S:	Supported
 F:	drivers/gpio/gpio-nct6694.c
+F:	drivers/i2c/busses/i2c-nct6694.c
 F:	drivers/mfd/nct6694.c
 F:	include/linux/mfd/nct6694.h
 
diff --git a/drivers/i2c/busses/Kconfig b/drivers/i2c/busses/Kconfig
index ceb3ecdf884b..a3f60e6953bd 100644
--- a/drivers/i2c/busses/Kconfig
+++ b/drivers/i2c/busses/Kconfig
@@ -1328,6 +1328,16 @@ config I2C_LJCA
 	  This driver can also be built as a module.  If so, the module
 	  will be called i2c-ljca.
 
+config I2C_NCT6694
+	tristate "Nuvoton NCT6694 I2C adapter support"
+	depends on MFD_NCT6694
+	help
+	  If you say yes to this option, support will be included for Nuvoton
+	  NCT6694, a USB to I2C interface.
+
+	  This driver can also be built as a module. If so, the module will
+	  be called i2c-nct6694.
+
 config I2C_CP2615
 	tristate "Silicon Labs CP2615 USB sound card and I2C adapter"
 	depends on USB
diff --git a/drivers/i2c/busses/Makefile b/drivers/i2c/busses/Makefile
index 1c2a4510abe4..c5a60116dd54 100644
--- a/drivers/i2c/busses/Makefile
+++ b/drivers/i2c/busses/Makefile
@@ -133,6 +133,7 @@ obj-$(CONFIG_I2C_GXP)		+= i2c-gxp.o
 obj-$(CONFIG_I2C_DIOLAN_U2C)	+= i2c-diolan-u2c.o
 obj-$(CONFIG_I2C_DLN2)		+= i2c-dln2.o
 obj-$(CONFIG_I2C_LJCA)		+= i2c-ljca.o
+obj-$(CONFIG_I2C_NCT6694)	+= i2c-nct6694.o
 obj-$(CONFIG_I2C_CP2615) += i2c-cp2615.o
 obj-$(CONFIG_I2C_PARPORT)	+= i2c-parport.o
 obj-$(CONFIG_I2C_PCI1XXXX)	+= i2c-mchp-pci1xxxx.o
diff --git a/drivers/i2c/busses/i2c-nct6694.c b/drivers/i2c/busses/i2c-nct6694.c
new file mode 100644
index 000000000000..9add97c407d8
--- /dev/null
+++ b/drivers/i2c/busses/i2c-nct6694.c
@@ -0,0 +1,156 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Nuvoton NCT6694 I2C adapter driver based on USB interface.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#include <linux/i2c.h>
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/nct6694.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+
+/*
+ * USB command module type for NCT6694 I2C controller.
+ * This defines the module type used for communication with the NCT6694
+ * I2C controller over the USB interface.
+ */
+#define NCT6694_I2C_MOD		0x03
+
+/* Command 00h - I2C Deliver */
+#define NCT6694_I2C_DELIVER     0x0000	/* SEL|CMD */
+
+enum i2c_baudrate {
+	I2C_BR_25K = 0,
+	I2C_BR_50K,
+	I2C_BR_100K,
+	I2C_BR_200K,
+	I2C_BR_400K,
+	I2C_BR_800K,
+	I2C_BR_1M
+};
+
+struct __packed nct6694_i2c_deliver {
+	u8 port;
+	u8 br;
+	u8 addr;
+	u8 w_cnt;
+	u8 r_cnt;
+	u8 rsv[11];
+	u8 write_data[0x40];
+	u8 read_data[0x40];
+};
+
+struct nct6694_i2c_data {
+	struct nct6694 *nct6694;
+	struct i2c_adapter adapter;
+	struct nct6694_i2c_deliver *deliver;
+	unsigned char port;
+	unsigned char br;
+};
+
+static int nct6694_xfer(struct i2c_adapter *adap, struct i2c_msg *msgs, int num)
+{
+	struct nct6694_i2c_data *data = adap->algo_data;
+	struct nct6694_i2c_deliver *deliver = data->deliver;
+	int ret, i;
+
+	for (i = 0; i < num ; i++) {
+		struct i2c_msg *msg_temp = &msgs[i];
+
+		memset(deliver, 0, sizeof(*deliver));
+
+		if (msg_temp->len > 64)
+			return -EPROTO;
+
+		deliver->port = data->port;
+		deliver->br = data->br;
+		deliver->addr = i2c_8bit_addr_from_msg(msg_temp);
+		if (msg_temp->flags & I2C_M_RD) {
+			deliver->r_cnt = msg_temp->len;
+			ret = nct6694_write_msg(data->nct6694, NCT6694_I2C_MOD,
+						NCT6694_I2C_DELIVER,
+						sizeof(*deliver),
+						deliver);
+			if (ret < 0)
+				return ret;
+
+			memcpy(msg_temp->buf, deliver->read_data, msg_temp->len);
+		} else {
+			deliver->w_cnt = msg_temp->len;
+			memcpy(deliver->write_data, msg_temp->buf, msg_temp->len);
+			ret = nct6694_write_msg(data->nct6694, NCT6694_I2C_MOD,
+						NCT6694_I2C_DELIVER,
+						sizeof(*deliver),
+						deliver);
+			if (ret < 0)
+				return ret;
+		}
+	}
+
+	return num;
+}
+
+static u32 nct6694_func(struct i2c_adapter *adapter)
+{
+	return I2C_FUNC_I2C | I2C_FUNC_SMBUS_EMUL;
+}
+
+static const struct i2c_algorithm algorithm = {
+	.master_xfer = nct6694_xfer,
+	.functionality = nct6694_func,
+};
+
+static int nct6694_i2c_probe(struct platform_device *pdev)
+{
+	const struct mfd_cell *cell = mfd_get_cell(pdev);
+	struct nct6694 *nct6694 = dev_get_drvdata(pdev->dev.parent);
+	struct nct6694_i2c_data *data;
+
+	data = devm_kzalloc(&pdev->dev, sizeof(*data), GFP_KERNEL);
+	if (!data)
+		return -ENOMEM;
+
+	data->deliver = devm_kzalloc(&pdev->dev, sizeof(struct nct6694_i2c_deliver),
+				     GFP_KERNEL);
+	if (!data->deliver)
+		return -ENOMEM;
+
+	data->nct6694 = nct6694;
+	data->port = cell->id;
+	data->br = I2C_BR_100K;
+
+	sprintf(data->adapter.name, "NCT6694 I2C Adapter %d", cell->id);
+	data->adapter.owner = THIS_MODULE;
+	data->adapter.algo = &algorithm;
+	data->adapter.dev.parent = &pdev->dev;
+	data->adapter.algo_data = data;
+
+	platform_set_drvdata(pdev, data);
+
+	return i2c_add_adapter(&data->adapter);
+}
+
+static void nct6694_i2c_remove(struct platform_device *pdev)
+{
+	struct nct6694_i2c_data *data = platform_get_drvdata(pdev);
+
+	i2c_del_adapter(&data->adapter);
+}
+
+static struct platform_driver nct6694_i2c_driver = {
+	.driver = {
+		.name	= "nct6694-i2c",
+	},
+	.probe		= nct6694_i2c_probe,
+	.remove		= nct6694_i2c_remove,
+};
+
+module_platform_driver(nct6694_i2c_driver);
+
+MODULE_DESCRIPTION("USB-I2C adapter driver for NCT6694");
+MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:nct6694-i2c");
-- 
2.34.1


^ permalink raw reply related	[flat|nested] 22+ messages in thread

* [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support
  2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
                   ` (2 preceding siblings ...)
  2024-12-27  9:57 ` [PATCH v4 3/7] i2c: Add Nuvoton NCT6694 I2C support Ming Yu
@ 2024-12-27  9:57 ` Ming Yu
  2024-12-27 15:59   ` Vincent Mailhol
  2024-12-30  5:56   ` Vincent Mailhol
  2024-12-27  9:57 ` [PATCH v4 5/7] watchdog: Add Nuvoton NCT6694 WDT support Ming Yu
                   ` (2 subsequent siblings)
  6 siblings, 2 replies; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

This driver supports Socket CANfd functionality for NCT6694 MFD
device based on USB interface.

Signed-off-by: Ming Yu <a0282524688@gmail.com>
---
 MAINTAINERS                     |   1 +
 drivers/net/can/Kconfig         |  10 +
 drivers/net/can/Makefile        |   1 +
 drivers/net/can/nct6694_canfd.c | 826 ++++++++++++++++++++++++++++++++
 4 files changed, 838 insertions(+)
 create mode 100644 drivers/net/can/nct6694_canfd.c

diff --git a/MAINTAINERS b/MAINTAINERS
index 5d63542233c4..b961c4827648 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -16729,6 +16729,7 @@ S:	Supported
 F:	drivers/gpio/gpio-nct6694.c
 F:	drivers/i2c/busses/i2c-nct6694.c
 F:	drivers/mfd/nct6694.c
+F:	drivers/net/can/nct6694_canfd.c
 F:	include/linux/mfd/nct6694.h
 
 NVIDIA (rivafb and nvidiafb) FRAMEBUFFER DRIVER
diff --git a/drivers/net/can/Kconfig b/drivers/net/can/Kconfig
index cf989bea9aa3..130e98ec28a5 100644
--- a/drivers/net/can/Kconfig
+++ b/drivers/net/can/Kconfig
@@ -200,6 +200,16 @@ config CAN_SUN4I
 	  To compile this driver as a module, choose M here: the module will
 	  be called sun4i_can.
 
+config CAN_NCT6694
+	tristate "Nuvoton NCT6694 Socket CANfd support"
+	depends on MFD_NCT6694
+	help
+	  If you say yes to this option, support will be included for Nuvoton
+	  NCT6694, a USB device to socket CANfd controller.
+
+	  This driver can also be built as a module. If so, the module will
+	  be called nct6694_canfd.
+
 config CAN_TI_HECC
 	depends on ARM
 	tristate "TI High End CAN Controller"
diff --git a/drivers/net/can/Makefile b/drivers/net/can/Makefile
index a71db2cfe990..4a6b5b9d6c2b 100644
--- a/drivers/net/can/Makefile
+++ b/drivers/net/can/Makefile
@@ -28,6 +28,7 @@ obj-$(CONFIG_CAN_JANZ_ICAN3)	+= janz-ican3.o
 obj-$(CONFIG_CAN_KVASER_PCIEFD)	+= kvaser_pciefd.o
 obj-$(CONFIG_CAN_MSCAN)		+= mscan/
 obj-$(CONFIG_CAN_M_CAN)		+= m_can/
+obj-$(CONFIG_CAN_NCT6694)	+= nct6694_canfd.o
 obj-$(CONFIG_CAN_PEAK_PCIEFD)	+= peak_canfd/
 obj-$(CONFIG_CAN_SJA1000)	+= sja1000/
 obj-$(CONFIG_CAN_SUN4I)		+= sun4i_can.o
diff --git a/drivers/net/can/nct6694_canfd.c b/drivers/net/can/nct6694_canfd.c
new file mode 100644
index 000000000000..94cfff288c14
--- /dev/null
+++ b/drivers/net/can/nct6694_canfd.c
@@ -0,0 +1,826 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Nuvoton NCT6694 Socket CANfd driver based on USB interface.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#include <linux/can/dev.h>
+#include <linux/can/rx-offload.h>
+#include <linux/ethtool.h>
+#include <linux/irqdomain.h>
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/nct6694.h>
+#include <linux/module.h>
+#include <linux/netdevice.h>
+#include <linux/platform_device.h>
+
+#define DRVNAME "nct6694-can"
+
+/*
+ * USB command module type for NCT6694 CANfd controller.
+ * This defines the module type used for communication with the NCT6694
+ * CANfd controller over the USB interface.
+ */
+#define NCT6694_CAN_MOD			0x05
+
+/* Command 00h - CAN Setting and Initialization */
+#define NCT6694_CAN_SETTING(idx)	(idx ? 0x0100 : 0x0000)	/* CMD|SEL */
+#define NCT6694_CAN_SETTING_CTRL1_MON	BIT(0)
+#define NCT6694_CAN_SETTING_CTRL1_NISO	BIT(1)
+#define NCT6694_CAN_SETTING_CTRL1_LBCK	BIT(2)
+
+/* Command 01h - CAN Information */
+#define NCT6694_CAN_INFORMATION		0x0001	/* CMD|SEL */
+
+/* Command 02h - CAN Event */
+#define NCT6694_CAN_EVENT(idx, mask)	\
+	((((idx ? 0x80 : 0x00) |	\
+	((mask) & 0xFF)) << 8) | 0x02)	/* CMD|SEL */
+#define NCT6694_CAN_EVENT_ERR		BIT(0)
+#define NCT6694_CAN_EVENT_STATUS	BIT(1)
+#define NCT6694_CAN_EVENT_TX_EVT	BIT(2)
+#define NCT6694_CAN_EVENT_RX_EVT	BIT(3)
+#define NCT6694_CAN_EVENT_REC		BIT(4)
+#define NCT6694_CAN_EVENT_TEC		BIT(5)
+#define NCT6694_CAN_EVENT_MASK          GENMASK(3, 0)
+#define NCT6694_CAN_EVT_TX_FIFO_EMPTY	BIT(7)	/* Read-clear */
+#define NCT6694_CAN_EVT_RX_DATA_LOST	BIT(5)	/* Read-clear */
+#define NCT6694_CAN_EVT_RX_HALF_FULL	BIT(6)	/* Read-clear */
+#define NCT6694_CAN_EVT_RX_DATA_IN	BIT(7)	/* Read-clear*/
+
+/* Command 10h - CAN Deliver */
+#define NCT6694_CAN_DELIVER(buf_cnt)	\
+	((((buf_cnt) & 0xFF) << 8) | 0x10)	/* CMD|SEL */
+
+/* Command 11h - CAN Receive */
+#define NCT6694_CAN_RECEIVE(idx, buf_cnt)	\
+	((((idx ? 0x80 : 0x00) |		\
+	((buf_cnt) & 0xFF)) << 8) | 0x11)	/* CMD|SEL */
+
+#define NCT6694_CAN_FRAME_TAG_CAN0	0xC0
+#define NCT6694_CAN_FRAME_TAG_CAN1	0xC1
+#define NCT6694_CAN_FRAME_FLAG_EFF	BIT(0)
+#define NCT6694_CAN_FRAME_FLAG_RTR	BIT(1)
+#define NCT6694_CAN_FRAME_FLAG_FD	BIT(2)
+#define NCT6694_CAN_FRAME_FLAG_BRS	BIT(3)
+#define NCT6694_CAN_FRAME_FLAG_ERR	BIT(4)
+
+#define NCT6694_NAPI_WEIGHT             32
+
+enum nct6694_event_err {
+	NCT6694_CAN_EVT_ERR_NO_ERROR,
+	NCT6694_CAN_EVT_ERR_CRC_ERROR,
+	NCT6694_CAN_EVT_ERR_STUFF_ERROR,
+	NCT6694_CAN_EVT_ERR_ACK_ERROR,
+	NCT6694_CAN_EVT_ERR_FORM_ERROR,
+	NCT6694_CAN_EVT_ERR_BIT_ERROR,
+	NCT6694_CAN_EVT_ERR_TIMEOUT_ERROR,
+	NCT6694_CAN_EVT_ERR_UNKNOWN_ERROR,
+};
+
+enum nct6694_event_status {
+	NCT6694_CAN_EVT_STS_ERROR_ACTIVE,
+	NCT6694_CAN_EVT_STS_ERROR_PASSIVE,
+	NCT6694_CAN_EVT_STS_BUS_OFF,
+	NCT6694_CAN_EVT_STS_WARNING,
+};
+
+struct __packed nct6694_can_setting {
+	__le32 nbr;
+	__le32 dbr;
+	u8 active;
+	u8 reserved[3];
+	__le16 ctrl1;
+	__le16 ctrl2;
+	__le32 nbtp;
+	__le32 dbtp;
+};
+
+struct __packed nct6694_can_information {
+	u8 tx_fifo_cnt;
+	u8 rx_fifo_cnt;
+	u8 reserved[2];
+	__le32 can_clk;
+};
+
+struct __packed nct6694_can_event_channel {
+	u8 err;
+	u8 status;
+	u8 tx_evt;
+	u8 rx_evt;
+	u8 rec;
+	u8 tec;
+	u8 reserved[2];
+};
+
+struct __packed nct6694_can_event {
+	struct nct6694_can_event_channel evt_ch[2];
+};
+
+struct __packed nct6694_can_frame {
+	u8 tag;
+	u8 flag;
+	u8 reserved;
+	u8 length;
+	__le32 id;
+	u8 data[64];
+};
+
+union nct6694_can_tx {
+	struct nct6694_can_frame frame;
+	struct nct6694_can_setting setting;
+};
+
+union nct6694_can_rx {
+	struct nct6694_can_event event;
+	struct nct6694_can_frame frame;
+	struct nct6694_can_information info;
+};
+
+struct nct6694_can_priv {
+	struct can_priv can;	/* must be the first member */
+	struct can_rx_offload offload;
+	struct net_device *ndev;
+	struct nct6694 *nct6694;
+	struct mutex lock;
+	struct sk_buff *tx_skb;
+	struct workqueue_struct *wq;
+	struct work_struct tx_work;
+	union nct6694_can_tx *tx;
+	union nct6694_can_rx *rx;
+	unsigned char can_idx;
+	bool tx_busy;
+};
+
+static inline struct nct6694_can_priv *rx_offload_to_priv(struct can_rx_offload *offload)
+{
+	return container_of(offload, struct nct6694_can_priv, offload);
+}
+
+static const struct can_bittiming_const nct6694_can_bittiming_nominal_const = {
+	.name = DRVNAME,
+	.tseg1_min = 2,
+	.tseg1_max = 256,
+	.tseg2_min = 2,
+	.tseg2_max = 128,
+	.sjw_max = 128,
+	.brp_min = 1,
+	.brp_max = 511,
+	.brp_inc = 1,
+};
+
+static const struct can_bittiming_const nct6694_can_bittiming_data_const = {
+	.name = DRVNAME,
+	.tseg1_min = 1,
+	.tseg1_max = 32,
+	.tseg2_min = 1,
+	.tseg2_max = 16,
+	.sjw_max = 16,
+	.brp_min = 1,
+	.brp_max = 31,
+	.brp_inc = 1,
+};
+
+static void nct6694_can_rx_offload(struct can_rx_offload *offload,
+				   struct sk_buff *skb)
+{
+	struct nct6694_can_priv *priv = rx_offload_to_priv(offload);
+	int ret;
+
+	ret = can_rx_offload_queue_tail(offload, skb);
+	if (ret)
+		priv->ndev->stats.rx_fifo_errors++;
+}
+
+static void nct6694_can_handle_lost_msg(struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct net_device_stats *stats = &ndev->stats;
+	struct can_frame *cf;
+	struct sk_buff *skb;
+
+	netdev_err(ndev, "RX FIFO overflow, message(s) lost.\n");
+
+	stats->rx_errors++;
+	stats->rx_over_errors++;
+
+	skb = alloc_can_err_skb(ndev, &cf);
+	if (!skb)
+		return;
+
+	cf->can_id |= CAN_ERR_CRTL;
+	cf->data[1] = CAN_ERR_CRTL_RX_OVERFLOW;
+
+	nct6694_can_rx_offload(&priv->offload, skb);
+}
+
+static void nct6694_can_rx(struct net_device *ndev, u8 rx_evt)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct nct6694_can_frame *frame = &priv->rx->frame;
+	struct canfd_frame *cfd;
+	struct can_frame *cf;
+	struct sk_buff *skb;
+	int ret;
+
+	ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
+			       NCT6694_CAN_RECEIVE(priv->can_idx, 1),
+			       sizeof(*frame), frame);
+	if (ret)
+		return;
+
+	if (frame->flag & NCT6694_CAN_FRAME_FLAG_FD) {
+		skb = alloc_canfd_skb(priv->ndev, &cfd);
+		if (!skb)
+			return;
+
+		cfd->can_id = le32_to_cpu(frame->id);
+		cfd->len = frame->length;
+		if (frame->flag & NCT6694_CAN_FRAME_FLAG_EFF)
+			cfd->can_id |= CAN_EFF_FLAG;
+		if (frame->flag & NCT6694_CAN_FRAME_FLAG_BRS)
+			cfd->flags |= CANFD_BRS;
+		if (frame->flag & NCT6694_CAN_FRAME_FLAG_ERR)
+			cfd->flags |= CANFD_ESI;
+
+		memcpy(cfd->data, frame->data, cfd->len);
+	} else {
+		skb = alloc_can_skb(priv->ndev, &cf);
+		if (!skb)
+			return;
+
+		cf->can_id = le32_to_cpu(frame->id);
+		cf->len = frame->length;
+		if (frame->flag & NCT6694_CAN_FRAME_FLAG_EFF)
+			cf->can_id |= CAN_EFF_FLAG;
+		if (frame->flag & NCT6694_CAN_FRAME_FLAG_RTR)
+			cf->can_id |= CAN_RTR_FLAG;
+
+		memcpy(cf->data, frame->data, cf->len);
+	}
+
+	nct6694_can_rx_offload(&priv->offload, skb);
+}
+
+static void nct6694_can_clean(struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+
+	if (priv->tx_skb || priv->tx_busy)
+		ndev->stats.tx_errors++;
+	dev_kfree_skb(priv->tx_skb);
+	if (priv->tx_busy)
+		can_free_echo_skb(priv->ndev, 0, NULL);
+	priv->tx_skb = NULL;
+	priv->tx_busy = false;
+}
+
+static int nct6694_can_get_berr_counter(const struct net_device *ndev,
+					struct can_berr_counter *bec)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct nct6694_can_event *evt = &priv->rx->event;
+	u8 mask = NCT6694_CAN_EVENT_REC | NCT6694_CAN_EVENT_TEC;
+	int ret;
+
+	guard(mutex)(&priv->lock);
+
+	ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
+			       NCT6694_CAN_EVENT(priv->can_idx, mask),
+			       sizeof(*evt),
+			       evt);
+	if (ret < 0)
+		return ret;
+
+	bec->rxerr = evt->evt_ch[priv->can_idx].rec;
+	bec->txerr = evt->evt_ch[priv->can_idx].tec;
+
+	return 0;
+}
+
+static void nct6694_can_handle_state_change(struct net_device *ndev,
+					    u8 status)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	enum can_state new_state = priv->can.state;
+	enum can_state rx_state, tx_state;
+	struct can_berr_counter bec;
+	struct can_frame *cf;
+	struct sk_buff *skb;
+
+	nct6694_can_get_berr_counter(ndev, &bec);
+	can_state_get_by_berr_counter(ndev, &bec, &tx_state, &rx_state);
+
+	if (status & NCT6694_CAN_EVT_STS_BUS_OFF)
+		new_state = CAN_STATE_BUS_OFF;
+	else if (status & NCT6694_CAN_EVT_STS_ERROR_PASSIVE)
+		new_state = CAN_STATE_ERROR_PASSIVE;
+	else if (status & NCT6694_CAN_EVT_STS_WARNING)
+		new_state = CAN_STATE_ERROR_WARNING;
+
+	/* state hasn't changed */
+	if (new_state == priv->can.state)
+		return;
+
+	skb = alloc_can_err_skb(ndev, &cf);
+
+	tx_state = bec.txerr >= bec.rxerr ? new_state : 0;
+	rx_state = bec.txerr <= bec.rxerr ? new_state : 0;
+	can_change_state(ndev, cf, tx_state, rx_state);
+
+	if (new_state == CAN_STATE_BUS_OFF) {
+		can_bus_off(ndev);
+	} else if (skb) {
+		cf->can_id |= CAN_ERR_CNT;
+		cf->data[6] = bec.txerr;
+		cf->data[7] = bec.rxerr;
+	}
+
+	nct6694_can_rx_offload(&priv->offload, skb);
+}
+
+static void nct6694_handle_bus_err(struct net_device *ndev, u8 bus_err)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct can_frame *cf;
+	struct sk_buff *skb;
+
+	if (bus_err == NCT6694_CAN_EVT_ERR_NO_ERROR)
+		return;
+
+	priv->can.can_stats.bus_error++;
+
+	skb = alloc_can_err_skb(ndev, &cf);
+	if (skb)
+		cf->can_id |= CAN_ERR_PROT | CAN_ERR_BUSERROR;
+
+	switch (bus_err) {
+	case NCT6694_CAN_EVT_ERR_CRC_ERROR:
+		netdev_dbg(ndev, "CRC error\n");
+		ndev->stats.rx_errors++;
+		if (skb)
+			cf->data[3] |= CAN_ERR_PROT_LOC_CRC_SEQ;
+		break;
+
+	case NCT6694_CAN_EVT_ERR_STUFF_ERROR:
+		netdev_dbg(ndev, "Stuff error\n");
+		ndev->stats.rx_errors++;
+		if (skb)
+			cf->data[2] |= CAN_ERR_PROT_STUFF;
+		break;
+
+	case NCT6694_CAN_EVT_ERR_ACK_ERROR:
+		netdev_dbg(ndev, "Ack error\n");
+		ndev->stats.tx_errors++;
+		if (skb) {
+			cf->can_id |= CAN_ERR_ACK;
+			cf->data[2] |= CAN_ERR_PROT_TX;
+		}
+		break;
+
+	case NCT6694_CAN_EVT_ERR_FORM_ERROR:
+		netdev_dbg(ndev, "Form error\n");
+		ndev->stats.rx_errors++;
+		if (skb)
+			cf->data[2] |= CAN_ERR_PROT_FORM;
+		break;
+
+	case NCT6694_CAN_EVT_ERR_BIT_ERROR:
+		netdev_dbg(ndev, "Bit error\n");
+		ndev->stats.tx_errors++;
+		if (skb)
+			cf->data[2] |= CAN_ERR_PROT_TX | CAN_ERR_PROT_BIT;
+		break;
+
+	default:
+		break;
+	}
+}
+
+static void nct6694_can_tx_irq(struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct net_device_stats *stats = &ndev->stats;
+
+	guard(mutex)(&priv->lock);
+	stats->tx_bytes += can_get_echo_skb(ndev, 0, NULL);
+	stats->tx_packets++;
+	priv->tx_busy = false;
+	netif_wake_queue(ndev);
+}
+
+static irqreturn_t nct6694_can_irq(int irq, void *data)
+{
+	struct net_device *ndev = data;
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct nct6694_can_event *evt = &priv->rx->event;
+	u8 tx_evt, rx_evt, bus_err, can_status;
+	u8 mask_sts = NCT6694_CAN_EVENT_MASK;
+	irqreturn_t handled = IRQ_NONE;
+	int can_idx = priv->can_idx;
+	int ret;
+
+	scoped_guard(mutex, &priv->lock) {
+		ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
+				       NCT6694_CAN_EVENT(can_idx, mask_sts),
+				       sizeof(*evt), evt);
+		if (ret < 0)
+			return handled;
+
+		tx_evt = evt->evt_ch[can_idx].tx_evt;
+		rx_evt = evt->evt_ch[can_idx].rx_evt;
+		bus_err = evt->evt_ch[can_idx].err;
+		can_status = evt->evt_ch[can_idx].status;
+	}
+
+	if (rx_evt & NCT6694_CAN_EVT_RX_DATA_IN) {
+		nct6694_can_rx(ndev, rx_evt);
+		handled = IRQ_HANDLED;
+	}
+
+	if (rx_evt & NCT6694_CAN_EVT_RX_DATA_LOST) {
+		nct6694_can_handle_lost_msg(ndev);
+		handled = IRQ_HANDLED;
+	}
+
+	if (can_status) {
+		nct6694_can_handle_state_change(ndev, can_status);
+		handled = IRQ_HANDLED;
+	}
+
+	if (priv->can.ctrlmode & CAN_CTRLMODE_BERR_REPORTING) {
+		nct6694_handle_bus_err(ndev, bus_err);
+		handled = IRQ_HANDLED;
+	}
+
+	if (handled)
+		can_rx_offload_threaded_irq_finish(&priv->offload);
+
+	if (tx_evt & NCT6694_CAN_EVT_TX_FIFO_EMPTY)
+		nct6694_can_tx_irq(ndev);
+
+	return handled;
+}
+
+static void nct6694_can_tx(struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct nct6694_can_frame *frame = &priv->tx->frame;
+	struct net_device_stats *stats = &ndev->stats;
+	struct sk_buff *skb = priv->tx_skb;
+	struct canfd_frame *cfd;
+	struct can_frame *cf;
+	u32 txid;
+	int err;
+
+	memset(frame, 0, sizeof(*frame));
+
+	if (priv->can_idx == 0)
+		frame->tag = NCT6694_CAN_FRAME_TAG_CAN0;
+	else
+		frame->tag = NCT6694_CAN_FRAME_TAG_CAN1;
+
+	if (can_is_canfd_skb(skb)) {
+		cfd = (struct canfd_frame *)priv->tx_skb->data;
+
+		if (cfd->flags & CANFD_BRS)
+			frame->flag |= NCT6694_CAN_FRAME_FLAG_BRS;
+
+		if (cfd->can_id & CAN_EFF_FLAG) {
+			txid = cfd->can_id & CAN_EFF_MASK;
+			frame->flag |= NCT6694_CAN_FRAME_FLAG_EFF;
+		} else {
+			txid = cfd->can_id & CAN_SFF_MASK;
+		}
+		frame->flag |= NCT6694_CAN_FRAME_FLAG_FD;
+		frame->id = cpu_to_le32(txid);
+		frame->length = cfd->len;
+
+		memcpy(frame->data, cfd->data, cfd->len);
+	} else {
+		cf = (struct can_frame *)priv->tx_skb->data;
+
+		if (cf->can_id & CAN_RTR_FLAG)
+			frame->flag |= NCT6694_CAN_FRAME_FLAG_RTR;
+
+		if (cf->can_id & CAN_EFF_FLAG) {
+			txid = cf->can_id & CAN_EFF_MASK;
+			frame->flag |= NCT6694_CAN_FRAME_FLAG_EFF;
+		} else {
+			txid = cf->can_id & CAN_SFF_MASK;
+		}
+		frame->id = cpu_to_le32(txid);
+		frame->length = cf->len;
+
+		memcpy(frame->data, cf->data, cf->len);
+		}
+
+	err = nct6694_write_msg(priv->nct6694, NCT6694_CAN_MOD,
+				NCT6694_CAN_DELIVER(1),
+				sizeof(*frame),
+				frame);
+	if (err) {
+		netdev_err(ndev, "%s: Tx FIFO full!\n", __func__);
+		can_free_echo_skb(ndev, 0, NULL);
+		stats->tx_dropped++;
+		stats->tx_errors++;
+		netif_wake_queue(ndev);
+	}
+}
+
+static void nct6694_can_tx_work(struct work_struct *work)
+{
+	struct nct6694_can_priv *priv = container_of(work,
+						     struct nct6694_can_priv,
+						     tx_work);
+	struct net_device *ndev = priv->ndev;
+
+	guard(mutex)(&priv->lock);
+
+	if (priv->tx_skb) {
+		if (priv->can.state == CAN_STATE_BUS_OFF) {
+			nct6694_can_clean(ndev);
+		} else {
+			nct6694_can_tx(ndev);
+			can_put_echo_skb(priv->tx_skb, ndev, 0, 0);
+			priv->tx_busy = true;
+			priv->tx_skb = NULL;
+		}
+	}
+}
+
+static netdev_tx_t nct6694_can_start_xmit(struct sk_buff *skb,
+					  struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+
+	if (can_dev_dropped_skb(ndev, skb))
+		return NETDEV_TX_OK;
+
+	if (priv->tx_skb || priv->tx_busy) {
+		netdev_err(ndev, "hard_xmit called while tx busy\n");
+		return NETDEV_TX_BUSY;
+	}
+
+	netif_stop_queue(ndev);
+	priv->tx_skb = skb;
+	queue_work(priv->wq, &priv->tx_work);
+
+	return NETDEV_TX_OK;
+}
+
+static int nct6694_can_start(struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	struct nct6694_can_setting *setting = &priv->tx->setting;
+	const struct can_bittiming *n_bt = &priv->can.bittiming;
+	const struct can_bittiming *d_bt = &priv->can.data_bittiming;
+	int ret;
+
+	guard(mutex)(&priv->lock);
+
+	memset(setting, 0, sizeof(*setting));
+	setting->nbr = cpu_to_le32(n_bt->bitrate);
+	setting->dbr = cpu_to_le32(d_bt->bitrate);
+
+	if (priv->can.ctrlmode & CAN_CTRLMODE_LISTENONLY)
+		setting->ctrl1 |= cpu_to_le16(NCT6694_CAN_SETTING_CTRL1_MON);
+
+	if ((priv->can.ctrlmode & CAN_CTRLMODE_FD) &&
+	    priv->can.ctrlmode & CAN_CTRLMODE_FD_NON_ISO)
+		setting->ctrl1 |= cpu_to_le16(NCT6694_CAN_SETTING_CTRL1_NISO);
+
+	if (priv->can.ctrlmode & CAN_CTRLMODE_LOOPBACK)
+		setting->ctrl1 |= cpu_to_le16(NCT6694_CAN_SETTING_CTRL1_LBCK);
+
+	ret = nct6694_write_msg(priv->nct6694, NCT6694_CAN_MOD,
+				NCT6694_CAN_SETTING(priv->can_idx),
+				sizeof(*setting), setting);
+	if (ret)
+		return ret;
+
+	priv->can.state = CAN_STATE_ERROR_ACTIVE;
+
+	return ret;
+}
+
+static int nct6694_can_stop(struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+
+	netif_stop_queue(ndev);
+	free_irq(ndev->irq, ndev);
+	destroy_workqueue(priv->wq);
+	priv->wq = NULL;
+	nct6694_can_clean(ndev);
+	priv->can.state = CAN_STATE_STOPPED;
+	can_rx_offload_disable(&priv->offload);
+	close_candev(ndev);
+
+	return 0;
+}
+
+static int nct6694_can_set_mode(struct net_device *ndev, enum can_mode mode)
+{
+	switch (mode) {
+	case CAN_MODE_START:
+		nct6694_can_clean(ndev);
+		nct6694_can_start(ndev);
+		netif_wake_queue(ndev);
+		break;
+	default:
+		return -EOPNOTSUPP;
+	}
+
+	return 0;
+}
+
+static int nct6694_can_open(struct net_device *ndev)
+{
+	struct nct6694_can_priv *priv = netdev_priv(ndev);
+	int ret;
+
+	ret = open_candev(ndev);
+	if (ret)
+		return ret;
+
+	can_rx_offload_enable(&priv->offload);
+
+	ret = request_threaded_irq(ndev->irq, NULL,
+				   nct6694_can_irq, IRQF_ONESHOT,
+				   "nct6694_can", ndev);
+	if (ret) {
+		netdev_err(ndev, "Failed to request IRQ\n");
+		goto close_candev;
+	}
+
+	priv->wq = alloc_ordered_workqueue("%s-nct6694_wq",
+					   WQ_FREEZABLE | WQ_MEM_RECLAIM,
+					   ndev->name);
+	if (!priv->wq) {
+		ret = -ENOMEM;
+		goto free_irq;
+	}
+
+	priv->tx_skb = NULL;
+	priv->tx_busy = false;
+
+	ret = nct6694_can_start(ndev);
+	if (ret)
+		goto destroy_wq;
+
+	netif_start_queue(ndev);
+
+	return 0;
+
+destroy_wq:
+	destroy_workqueue(priv->wq);
+free_irq:
+	free_irq(ndev->irq, ndev);
+close_candev:
+	can_rx_offload_disable(&priv->offload);
+	close_candev(ndev);
+	return ret;
+}
+
+static const struct net_device_ops nct6694_can_netdev_ops = {
+	.ndo_open = nct6694_can_open,
+	.ndo_stop = nct6694_can_stop,
+	.ndo_start_xmit = nct6694_can_start_xmit,
+	.ndo_change_mtu = can_change_mtu,
+};
+
+static const struct ethtool_ops nct6694_can_ethtool_ops = {
+	.get_ts_info = ethtool_op_get_ts_info,
+};
+
+static int nct6694_can_get_clock(struct nct6694_can_priv *priv)
+{
+	struct nct6694_can_information *info = &priv->rx->info;
+	int ret;
+
+	ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
+			       NCT6694_CAN_INFORMATION,
+			       sizeof(*info),
+			       info);
+	if (ret)
+		return ret;
+
+	return le32_to_cpu(info->can_clk);
+}
+
+static int nct6694_can_probe(struct platform_device *pdev)
+{
+	const struct mfd_cell *cell = mfd_get_cell(pdev);
+	struct nct6694 *nct6694 = dev_get_drvdata(pdev->dev.parent);
+	struct nct6694_can_priv *priv;
+	struct net_device *ndev;
+	int ret, irq, can_clk;
+
+	irq = irq_create_mapping(nct6694->domain,
+				 NCT6694_IRQ_CAN1 + cell->id);
+	if (!irq)
+		return irq;
+
+	ndev = alloc_candev(sizeof(struct nct6694_can_priv), 1);
+	if (!ndev)
+		return -ENOMEM;
+
+	ndev->irq = irq;
+	ndev->flags |= IFF_ECHO;
+	ndev->netdev_ops = &nct6694_can_netdev_ops;
+	ndev->ethtool_ops = &nct6694_can_ethtool_ops;
+
+	priv = netdev_priv(ndev);
+	priv->nct6694 = nct6694;
+	priv->ndev = ndev;
+
+	priv->tx = devm_kzalloc(&pdev->dev, sizeof(union nct6694_can_tx),
+				GFP_KERNEL);
+	if (!priv->tx) {
+		ret = -ENOMEM;
+		goto free_candev;
+	}
+
+	priv->rx = devm_kzalloc(&pdev->dev, sizeof(union nct6694_can_rx),
+				GFP_KERNEL);
+	if (!priv->rx) {
+		ret = -ENOMEM;
+		goto free_candev;
+	}
+
+	can_clk = nct6694_can_get_clock(priv);
+	if (can_clk < 0) {
+		ret = dev_err_probe(&pdev->dev, can_clk,
+				    "Failed to get clock\n");
+		goto free_candev;
+	}
+
+	devm_mutex_init(&pdev->dev, &priv->lock);
+	INIT_WORK(&priv->tx_work, nct6694_can_tx_work);
+
+	priv->can_idx = cell->id;
+	priv->can.state = CAN_STATE_STOPPED;
+	priv->can.clock.freq = can_clk;
+	priv->can.bittiming_const = &nct6694_can_bittiming_nominal_const;
+	priv->can.data_bittiming_const = &nct6694_can_bittiming_data_const;
+	priv->can.do_set_mode = nct6694_can_set_mode;
+	priv->can.do_get_berr_counter = nct6694_can_get_berr_counter;
+
+	priv->can.ctrlmode = CAN_CTRLMODE_FD;
+
+	priv->can.ctrlmode_supported = CAN_CTRLMODE_LOOPBACK		|
+				       CAN_CTRLMODE_LISTENONLY		|
+				       CAN_CTRLMODE_FD			|
+				       CAN_CTRLMODE_FD_NON_ISO		|
+				       CAN_CTRLMODE_BERR_REPORTING;
+
+	ret = can_rx_offload_add_manual(ndev, &priv->offload,
+					NCT6694_NAPI_WEIGHT);
+	if (ret) {
+		dev_err_probe(&pdev->dev, ret, "Failed to add rx_offload\n");
+		goto free_candev;
+	}
+
+	platform_set_drvdata(pdev, priv);
+	SET_NETDEV_DEV(priv->ndev, &pdev->dev);
+
+	ret = register_candev(priv->ndev);
+	if (ret)
+		goto del_rx_offload;
+
+	return 0;
+
+del_rx_offload:
+	can_rx_offload_del(&priv->offload);
+free_candev:
+	free_candev(ndev);
+	return ret;
+}
+
+static void nct6694_can_remove(struct platform_device *pdev)
+{
+	struct nct6694_can_priv *priv = platform_get_drvdata(pdev);
+
+	cancel_work_sync(&priv->tx_work);
+	unregister_candev(priv->ndev);
+	can_rx_offload_del(&priv->offload);
+	free_candev(priv->ndev);
+}
+
+static struct platform_driver nct6694_can_driver = {
+	.driver = {
+		.name	= DRVNAME,
+	},
+	.probe		= nct6694_can_probe,
+	.remove		= nct6694_can_remove,
+};
+
+module_platform_driver(nct6694_can_driver);
+
+MODULE_DESCRIPTION("USB-CAN FD driver for NCT6694");
+MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:nct6694-can");
-- 
2.34.1


^ permalink raw reply related	[flat|nested] 22+ messages in thread

* [PATCH v4 5/7] watchdog: Add Nuvoton NCT6694 WDT support
  2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
                   ` (3 preceding siblings ...)
  2024-12-27  9:57 ` [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support Ming Yu
@ 2024-12-27  9:57 ` Ming Yu
  2024-12-27  9:57 ` [PATCH v4 6/7] hwmon: Add Nuvoton NCT6694 HWMON support Ming Yu
  2024-12-27  9:57 ` [PATCH v4 7/7] rtc: Add Nuvoton NCT6694 RTC support Ming Yu
  6 siblings, 0 replies; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

This driver supports Watchdog timer functionality for NCT6694 MFD
device based on USB interface.

Signed-off-by: Ming Yu <a0282524688@gmail.com>
---
 MAINTAINERS                    |   1 +
 drivers/watchdog/Kconfig       |  11 ++
 drivers/watchdog/Makefile      |   1 +
 drivers/watchdog/nct6694_wdt.c | 281 +++++++++++++++++++++++++++++++++
 4 files changed, 294 insertions(+)
 create mode 100644 drivers/watchdog/nct6694_wdt.c

diff --git a/MAINTAINERS b/MAINTAINERS
index b961c4827648..254c01a6bba1 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -16730,6 +16730,7 @@ F:	drivers/gpio/gpio-nct6694.c
 F:	drivers/i2c/busses/i2c-nct6694.c
 F:	drivers/mfd/nct6694.c
 F:	drivers/net/can/nct6694_canfd.c
+F:	drivers/watchdog/nct6694_wdt.c
 F:	include/linux/mfd/nct6694.h
 
 NVIDIA (rivafb and nvidiafb) FRAMEBUFFER DRIVER
diff --git a/drivers/watchdog/Kconfig b/drivers/watchdog/Kconfig
index f81705f8539a..9471a39b97ab 100644
--- a/drivers/watchdog/Kconfig
+++ b/drivers/watchdog/Kconfig
@@ -748,6 +748,17 @@ config MAX77620_WATCHDOG
 	  MAX77620 chips. To compile this driver as a module,
 	  choose M here: the module will be called max77620_wdt.
 
+config NCT6694_WATCHDOG
+	tristate "Nuvoton NCT6694 watchdog support"
+	depends on MFD_NCT6694
+	select WATCHDOG_CORE
+	help
+	  Say Y here to support Nuvoton NCT6694 watchdog timer
+	  functionality.
+
+ 	  This driver can also be built as a module. If so, the module
+	  will be called nct6694_wdt.
+
 config IMX2_WDT
 	tristate "IMX2+ Watchdog"
 	depends on ARCH_MXC || ARCH_LAYERSCAPE || COMPILE_TEST
diff --git a/drivers/watchdog/Makefile b/drivers/watchdog/Makefile
index 8411626fa162..de2a04ff8a92 100644
--- a/drivers/watchdog/Makefile
+++ b/drivers/watchdog/Makefile
@@ -232,6 +232,7 @@ obj-$(CONFIG_WM831X_WATCHDOG) += wm831x_wdt.o
 obj-$(CONFIG_WM8350_WATCHDOG) += wm8350_wdt.o
 obj-$(CONFIG_MAX63XX_WATCHDOG) += max63xx_wdt.o
 obj-$(CONFIG_MAX77620_WATCHDOG) += max77620_wdt.o
+obj-$(CONFIG_NCT6694_WATCHDOG) += nct6694_wdt.o
 obj-$(CONFIG_ZIIRAVE_WATCHDOG) += ziirave_wdt.o
 obj-$(CONFIG_SOFT_WATCHDOG) += softdog.o
 obj-$(CONFIG_MENF21BMC_WATCHDOG) += menf21bmc_wdt.o
diff --git a/drivers/watchdog/nct6694_wdt.c b/drivers/watchdog/nct6694_wdt.c
new file mode 100644
index 000000000000..58171b9de982
--- /dev/null
+++ b/drivers/watchdog/nct6694_wdt.c
@@ -0,0 +1,281 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Nuvoton NCT6694 WDT driver based on USB interface.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/nct6694.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/slab.h>
+#include <linux/watchdog.h>
+
+#define DRVNAME "nct6694-wdt"
+
+#define NCT6694_DEFAULT_TIMEOUT		10
+#define NCT6694_DEFAULT_PRETIMEOUT	0
+
+/*
+ * USB command module type for NCT6694 WDT controller.
+ * This defines the module type used for communication with the NCT6694
+ * WDT controller over the USB interface.
+ */
+#define NCT6694_WDT_MOD			0x07
+
+/* Command 00h - WDT Setup */
+#define NCT6694_WDT_SETUP(idx)          (idx ? 0x0100 : 0x0000)	/* SEL|CMD */
+
+/* Command 01h - WDT Command */
+#define NCT6694_WDT_COMMAND(idx)        (idx ? 0x0101 : 0x0001)	/* SEL|CMD */
+
+static unsigned int timeout = NCT6694_DEFAULT_TIMEOUT;
+module_param(timeout, int, 0);
+MODULE_PARM_DESC(timeout, "Watchdog timeout in seconds");
+
+static unsigned int pretimeout = NCT6694_DEFAULT_PRETIMEOUT;
+module_param(pretimeout, int, 0);
+MODULE_PARM_DESC(pretimeout, "Watchdog pre-timeout in seconds");
+
+static bool nowayout = WATCHDOG_NOWAYOUT;
+module_param(nowayout, bool, 0);
+MODULE_PARM_DESC(nowayout, "Watchdog cannot be stopped once started (default="
+			   __MODULE_STRING(WATCHDOG_NOWAYOUT) ")");
+
+enum {
+	NCT6694_ACTION_NONE = 0,
+	NCT6694_ACTION_SIRQ,
+	NCT6694_ACTION_GPO,
+};
+
+struct __packed nct6694_wdt_setup {
+	__le32 pretimeout;
+	__le32 timeout;
+	u8 owner;
+	u8 scratch;
+	u8 control;
+	u8 status;
+	__le32 countdown;
+};
+
+struct __packed nct6694_wdt_cmd {
+	__le32 wdt_cmd;
+	__le32 reserved;
+};
+
+union nct6694_wdt_msg {
+	struct nct6694_wdt_setup setup;
+	struct nct6694_wdt_cmd cmd;
+};
+
+struct nct6694_wdt_data {
+	struct watchdog_device wdev;
+	struct device *dev;
+	struct nct6694 *nct6694;
+	struct mutex lock;
+	union nct6694_wdt_msg *msg;
+	unsigned int wdev_idx;
+};
+
+static int nct6694_wdt_setting(struct watchdog_device *wdev,
+			       u32 timeout_val, u8 timeout_act,
+			       u32 pretimeout_val, u8 pretimeout_act)
+{
+	struct nct6694_wdt_data *data = watchdog_get_drvdata(wdev);
+	struct nct6694_wdt_setup *setup = &data->msg->setup;
+	struct nct6694 *nct6694 = data->nct6694;
+	unsigned int timeout_fmt, pretimeout_fmt;
+
+	guard(mutex)(&data->lock);
+
+	if (pretimeout_val == 0)
+		pretimeout_act = NCT6694_ACTION_NONE;
+
+	timeout_fmt = (timeout_val * 1000) | (timeout_act << 24);
+	pretimeout_fmt = (pretimeout_val * 1000) | (pretimeout_act << 24);
+
+	memset(setup, 0, sizeof(*setup));
+	setup->timeout = cpu_to_le32(timeout_fmt);
+	setup->pretimeout = cpu_to_le32(pretimeout_fmt);
+
+	return nct6694_write_msg(nct6694, NCT6694_WDT_MOD,
+				 NCT6694_WDT_SETUP(data->wdev_idx),
+				 sizeof(*setup), setup);
+}
+
+static int nct6694_wdt_start(struct watchdog_device *wdev)
+{
+	struct nct6694_wdt_data *data = watchdog_get_drvdata(wdev);
+	int ret;
+
+	ret = nct6694_wdt_setting(wdev, wdev->timeout, NCT6694_ACTION_GPO,
+				  wdev->pretimeout, NCT6694_ACTION_GPO);
+	if (ret)
+		return ret;
+
+	dev_dbg(data->dev, "Setting WDT(%d): timeout = %d, pretimeout = %d\n",
+		data->wdev_idx, wdev->timeout, wdev->pretimeout);
+
+	return ret;
+}
+
+static int nct6694_wdt_stop(struct watchdog_device *wdev)
+{
+	struct nct6694_wdt_data *data = watchdog_get_drvdata(wdev);
+	struct nct6694_wdt_cmd *cmd = &data->msg->cmd;
+	struct nct6694 *nct6694 = data->nct6694;
+
+	guard(mutex)(&data->lock);
+
+	memcpy(&cmd->wdt_cmd, "WDTC", 4);
+	cmd->reserved = 0;
+
+	return nct6694_write_msg(nct6694, NCT6694_WDT_MOD,
+				 NCT6694_WDT_COMMAND(data->wdev_idx),
+				 sizeof(*cmd), cmd);
+}
+
+static int nct6694_wdt_ping(struct watchdog_device *wdev)
+{
+	struct nct6694_wdt_data *data = watchdog_get_drvdata(wdev);
+	struct nct6694_wdt_cmd *cmd = &data->msg->cmd;
+	struct nct6694 *nct6694 = data->nct6694;
+
+	guard(mutex)(&data->lock);
+	memcpy(&cmd->wdt_cmd, "WDTS", 4);
+	cmd->reserved = 0;
+
+	return nct6694_write_msg(nct6694, NCT6694_WDT_MOD,
+				 NCT6694_WDT_COMMAND(data->wdev_idx),
+				 sizeof(*cmd), cmd);
+}
+
+static int nct6694_wdt_set_timeout(struct watchdog_device *wdev,
+				   unsigned int timeout)
+{
+	int ret;
+
+	ret = nct6694_wdt_setting(wdev, timeout, NCT6694_ACTION_GPO,
+				  wdev->pretimeout, NCT6694_ACTION_GPO);
+	if (ret)
+		return ret;
+
+	wdev->timeout = timeout;
+
+	return 0;
+}
+
+static int nct6694_wdt_set_pretimeout(struct watchdog_device *wdev,
+				      unsigned int pretimeout)
+{
+	int ret;
+
+	ret = nct6694_wdt_setting(wdev, wdev->timeout, NCT6694_ACTION_GPO,
+				  pretimeout, NCT6694_ACTION_GPO);
+	if (ret)
+		return ret;
+
+	wdev->pretimeout = pretimeout;
+
+	return 0;
+}
+
+static unsigned int nct6694_wdt_get_time(struct watchdog_device *wdev)
+{
+	struct nct6694_wdt_data *data = watchdog_get_drvdata(wdev);
+	struct nct6694_wdt_setup *setup = &data->msg->setup;
+	struct nct6694 *nct6694 = data->nct6694;
+	unsigned int timeleft_ms;
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	ret = nct6694_read_msg(nct6694, NCT6694_WDT_MOD,
+			       NCT6694_WDT_SETUP(data->wdev_idx),
+			       sizeof(*setup), setup);
+	if (ret)
+		return 0;
+
+	timeleft_ms = le32_to_cpu(setup->countdown);
+
+	return timeleft_ms / 1000;
+}
+
+static const struct watchdog_info nct6694_wdt_info = {
+	.options = WDIOF_SETTIMEOUT	|
+		   WDIOF_KEEPALIVEPING	|
+		   WDIOF_MAGICCLOSE	|
+		   WDIOF_PRETIMEOUT,
+	.identity = DRVNAME,
+};
+
+static const struct watchdog_ops nct6694_wdt_ops = {
+	.owner = THIS_MODULE,
+	.start = nct6694_wdt_start,
+	.stop = nct6694_wdt_stop,
+	.set_timeout = nct6694_wdt_set_timeout,
+	.set_pretimeout = nct6694_wdt_set_pretimeout,
+	.get_timeleft = nct6694_wdt_get_time,
+	.ping = nct6694_wdt_ping,
+};
+
+static int nct6694_wdt_probe(struct platform_device *pdev)
+{
+	const struct mfd_cell *cell = mfd_get_cell(pdev);
+	struct device *dev = &pdev->dev;
+	struct nct6694 *nct6694 = dev_get_drvdata(pdev->dev.parent);
+	struct nct6694_wdt_data *data;
+	struct watchdog_device *wdev;
+
+	data = devm_kzalloc(&pdev->dev, sizeof(*data), GFP_KERNEL);
+	if (!data)
+		return -ENOMEM;
+
+	data->msg = devm_kzalloc(dev, sizeof(union nct6694_wdt_msg),
+				 GFP_KERNEL);
+	if (!data->msg)
+		return -ENOMEM;
+
+	data->dev = dev;
+	data->nct6694 = nct6694;
+	data->wdev_idx = cell->id;
+
+	wdev = &data->wdev;
+	wdev->info = &nct6694_wdt_info;
+	wdev->ops = &nct6694_wdt_ops;
+	wdev->timeout = timeout;
+	wdev->pretimeout = pretimeout;
+	if (timeout < pretimeout) {
+		dev_warn(data->dev, "pretimeout < timeout. Setting to zero\n");
+		wdev->pretimeout = 0;
+	}
+
+	wdev->min_timeout = 1;
+	wdev->max_timeout = 255;
+
+	devm_mutex_init(dev, &data->lock);
+
+	platform_set_drvdata(pdev, data);
+
+	watchdog_set_drvdata(&data->wdev, data);
+	watchdog_set_nowayout(&data->wdev, nowayout);
+	watchdog_stop_on_reboot(&data->wdev);
+
+	return devm_watchdog_register_device(dev, &data->wdev);
+}
+
+static struct platform_driver nct6694_wdt_driver = {
+	.driver = {
+		.name	= DRVNAME,
+	},
+	.probe		= nct6694_wdt_probe,
+};
+
+module_platform_driver(nct6694_wdt_driver);
+
+MODULE_DESCRIPTION("USB-WDT driver for NCT6694");
+MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:nct6694-wdt");
-- 
2.34.1


^ permalink raw reply related	[flat|nested] 22+ messages in thread

* [PATCH v4 6/7] hwmon: Add Nuvoton NCT6694 HWMON support
  2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
                   ` (4 preceding siblings ...)
  2024-12-27  9:57 ` [PATCH v4 5/7] watchdog: Add Nuvoton NCT6694 WDT support Ming Yu
@ 2024-12-27  9:57 ` Ming Yu
  2025-01-06 13:51   ` Simon Horman
  2024-12-27  9:57 ` [PATCH v4 7/7] rtc: Add Nuvoton NCT6694 RTC support Ming Yu
  6 siblings, 1 reply; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

This driver supports Hardware monitor functionality for NCT6694 MFD
device based on USB interface.

Signed-off-by: Ming Yu <a0282524688@gmail.com>
---
 MAINTAINERS                   |   1 +
 drivers/hwmon/Kconfig         |  10 +
 drivers/hwmon/Makefile        |   1 +
 drivers/hwmon/nct6694-hwmon.c | 851 ++++++++++++++++++++++++++++++++++
 4 files changed, 863 insertions(+)
 create mode 100644 drivers/hwmon/nct6694-hwmon.c

diff --git a/MAINTAINERS b/MAINTAINERS
index 254c01a6bba1..e5c65e382141 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -16727,6 +16727,7 @@ M:	Ming Yu <tmyu0@nuvoton.com>
 L:	linux-kernel@vger.kernel.org
 S:	Supported
 F:	drivers/gpio/gpio-nct6694.c
+F:	drivers/hwmon/nct6694-hwmon.c
 F:	drivers/i2c/busses/i2c-nct6694.c
 F:	drivers/mfd/nct6694.c
 F:	drivers/net/can/nct6694_canfd.c
diff --git a/drivers/hwmon/Kconfig b/drivers/hwmon/Kconfig
index dd376602f3f1..df40986424bd 100644
--- a/drivers/hwmon/Kconfig
+++ b/drivers/hwmon/Kconfig
@@ -1636,6 +1636,16 @@ config SENSORS_NCT6683
 	  This driver can also be built as a module. If so, the module
 	  will be called nct6683.
 
+config SENSORS_NCT6694
+	tristate "Nuvoton NCT6694 Hardware Monitor support"
+	depends on MFD_NCT6694
+	help
+	  Say Y here to support Nuvoton NCT6694 hardware monitoring
+	  functionality.
+
+	  This driver can also be built as a module. If so, the module
+	  will be called nct6694-hwmon.
+
 config SENSORS_NCT6775_CORE
 	tristate
 	select REGMAP
diff --git a/drivers/hwmon/Makefile b/drivers/hwmon/Makefile
index b827b92f2a78..27a43e67cdb7 100644
--- a/drivers/hwmon/Makefile
+++ b/drivers/hwmon/Makefile
@@ -168,6 +168,7 @@ obj-$(CONFIG_SENSORS_MLXREG_FAN) += mlxreg-fan.o
 obj-$(CONFIG_SENSORS_MENF21BMC_HWMON) += menf21bmc_hwmon.o
 obj-$(CONFIG_SENSORS_MR75203)	+= mr75203.o
 obj-$(CONFIG_SENSORS_NCT6683)	+= nct6683.o
+obj-$(CONFIG_SENSORS_NCT6694)	+= nct6694-hwmon.o
 obj-$(CONFIG_SENSORS_NCT6775_CORE) += nct6775-core.o
 nct6775-objs			:= nct6775-platform.o
 obj-$(CONFIG_SENSORS_NCT6775)	+= nct6775.o
diff --git a/drivers/hwmon/nct6694-hwmon.c b/drivers/hwmon/nct6694-hwmon.c
new file mode 100644
index 000000000000..a11d495e2875
--- /dev/null
+++ b/drivers/hwmon/nct6694-hwmon.c
@@ -0,0 +1,851 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Nuvoton NCT6694 HWMON driver based on USB interface.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#include <linux/bits.h>
+#include <linux/bitfield.h>
+#include <linux/hwmon.h>
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/nct6694.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/slab.h>
+
+/*
+ * USB command module type for NCT6694 report channel
+ * This defines the module type used for communication with the NCT6694
+ * report channel over the USB interface.
+ */
+#define NCT6694_RPT_MOD			0xFF
+
+/* Report channel */
+/*
+ * The report channel is used to report the status of the hardware monitor
+ * devices, such as voltage, temperature, fan speed, and PWM.
+ */
+#define NCT6694_VIN_IDX(x)		(0x00 + (x))		/* OFFSET */
+#define NCT6694_TIN_IDX(x)			\
+	({ typeof(x) (_x) = (x);		\
+	 ((_x) < 10) ? (0x10 + ((_x) * 2)) :	\
+	 (0x30 + (((_x) - 10) * 2)); })				/* OFFSET */
+#define NCT6694_FIN_IDX(x)		(0x50 + ((x) * 2))	/* OFFSET */
+#define NCT6694_PWM_IDX(x)		(0x70 + (x))		/* OFFSET */
+#define NCT6694_VIN_STS(x)		(0x68 + (x))		/* OFFSET */
+#define NCT6694_TIN_STS(x)		(0x6A + (x))		/* OFFSET */
+#define NCT6694_FIN_STS(x)		(0x6E + (x))		/* OFFSET */
+
+/*
+ * USB command module type for NCT6694 HWMON controller.
+ * This defines the module type used for communication with the NCT6694
+ * HWMON controller over the USB interface.
+ */
+#define NCT6694_HWMON_MOD		0x00
+
+/* Command 00h - Hardware Monitor Control */
+#define NCT6694_HWMON_CONTROL	        0x0000	/* SEL|CMD */
+
+/* Command 02h - Alarm Control */
+#define NCT6694_HWMON_ALARM	        0x0002	/* SEL|CMD */
+
+/*
+ * USB command module type for NCT6694 PWM controller.
+ * This defines the module type used for communication with the NCT6694
+ * PWM controller over the USB interface.
+ */
+#define NCT6694_PWM_MOD			0x01
+
+/* PWM Command - Manual Control */
+#define NCT6694_PWM_CONTROL	        0x0001	/* SEL|CMD */
+
+#define NCT6694_FREQ_FROM_REG(reg)	((reg) * 25000 / 255)
+#define NCT6694_FREQ_TO_REG(val)	\
+	(DIV_ROUND_CLOSEST(clamp_val((val), 100, 25000) * 255, 25000))
+
+#define NCT6694_LSB_REG_MASK		GENMASK(7, 5)
+#define NCT6694_TIN_HYST_MASK		GENMASK(7, 5)
+
+enum nct6694_hwmon_temp_mode {
+	NCT6694_HWMON_TWOTIME_IRQ = 0,
+	NCT6694_HWMON_ONETIME_IRQ,
+	NCT6694_HWMON_REALTIME_IRQ,
+	NCT6694_HWMON_COMPARE_IRQ,
+};
+
+struct __packed nct6694_hwmon_control {
+	u8 vin_en[2];
+	u8 tin_en[2];
+	u8 fin_en[2];
+	u8 pwm_en[2];
+	u8 reserved1[40];
+	u8 pwm_freq[10];
+	u8 reserved2[6];
+};
+
+struct __packed nct6694_hwmon_alarm {
+	u8 smi_ctrl;
+	u8 reserved1[15];
+	struct {
+		u8 hl;
+		u8 ll;
+	} vin_limit[16];
+	struct {
+		u8 hyst;
+		s8 hl;
+	} tin_cfg[32];
+	__be16 fin_ll[10];
+	u8 reserved2[4];
+};
+
+struct __packed nct6694_pwm_control {
+	u8 mal_en[2];
+	u8 mal_val[10];
+	u8 reserved[12];
+};
+
+union nct6694_hwmon_rpt {
+	u8 vin;
+	struct {
+		u8 msb;
+		u8 lsb;
+	} tin;
+	__be16 fin;
+	u8 pwm;
+	u8 status;
+};
+
+union nct6694_hwmon_msg {
+	struct nct6694_hwmon_control hwmon_ctrl;
+	struct nct6694_hwmon_alarm hwmon_alarm;
+	struct nct6694_pwm_control pwm_ctrl;
+};
+
+struct nct6694_hwmon_data {
+	struct nct6694 *nct6694;
+	struct mutex lock;
+	struct nct6694_hwmon_control hwmon_en;
+	union nct6694_hwmon_rpt *rpt;
+	union nct6694_hwmon_msg *msg;
+};
+
+static inline long in_from_reg(u8 reg)
+{
+	return reg * 16;
+}
+
+static inline u8 in_to_reg(long val)
+{
+	return DIV_ROUND_CLOSEST(val, 16);
+}
+
+static inline long temp_from_reg(s8 reg)
+{
+	return reg * 1000;
+}
+
+static inline s8 temp_to_reg(long val)
+{
+	return DIV_ROUND_CLOSEST(val, 1000);
+}
+
+#define NCT6694_HWMON_IN_CONFIG (HWMON_I_INPUT | HWMON_I_ENABLE |	\
+				 HWMON_I_MAX | HWMON_I_MIN |		\
+				 HWMON_I_ALARM)
+#define NCT6694_HWMON_TEMP_CONFIG (HWMON_T_INPUT | HWMON_T_ENABLE |	\
+				   HWMON_T_MAX | HWMON_T_MAX_HYST |	\
+				   HWMON_T_MAX_ALARM)
+#define NCT6694_HWMON_FAN_CONFIG (HWMON_F_INPUT | HWMON_F_ENABLE |	\
+				  HWMON_F_MIN | HWMON_F_MIN_ALARM)
+#define NCT6694_HWMON_PWM_CONFIG (HWMON_PWM_INPUT | HWMON_PWM_ENABLE |	\
+				  HWMON_PWM_FREQ)
+static const struct hwmon_channel_info *nct6694_info[] = {
+	HWMON_CHANNEL_INFO(in,
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN0 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN1 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN2 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN3 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN5 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN6 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN7 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN14 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN15 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VIN16 */
+			   NCT6694_HWMON_IN_CONFIG,	/* VBAT */
+			   NCT6694_HWMON_IN_CONFIG,	/* VSB */
+			   NCT6694_HWMON_IN_CONFIG,	/* AVSB */
+			   NCT6694_HWMON_IN_CONFIG,	/* VCC */
+			   NCT6694_HWMON_IN_CONFIG,	/* VHIF */
+			   NCT6694_HWMON_IN_CONFIG),	/* VTT */
+
+	HWMON_CHANNEL_INFO(temp,
+			   NCT6694_HWMON_TEMP_CONFIG,	/* THR1 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* THR2 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* THR14 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* THR15 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* THR16 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* TDP0 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* TDP1 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* TDP2 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* TDP3 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* TDP4 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN0 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN1 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN2 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN3 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN4 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN5 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN6 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN7 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN8 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN9 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN10 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN11 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN12 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN13 */
+			   NCT6694_HWMON_TEMP_CONFIG,	/* DTIN14 */
+			   NCT6694_HWMON_TEMP_CONFIG),	/* DTIN15 */
+
+	HWMON_CHANNEL_INFO(fan,
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN0 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN1 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN2 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN3 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN4 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN5 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN6 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN7 */
+			   NCT6694_HWMON_FAN_CONFIG,	/* FIN8 */
+			   NCT6694_HWMON_FAN_CONFIG),	/* FIN9 */
+
+	HWMON_CHANNEL_INFO(pwm,
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM0 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM1 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM2 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM3 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM4 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM5 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM6 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM7 */
+			   NCT6694_HWMON_PWM_CONFIG,	/* PWM8 */
+			   NCT6694_HWMON_PWM_CONFIG),	/* PWM9 */
+	NULL
+};
+
+static int nct6694_in_read(struct device *dev, u32 attr, int channel,
+			   long *val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	unsigned char vin_en;
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_in_enable:
+		vin_en = data->hwmon_en.vin_en[(channel / 8)];
+		*val = !!(vin_en & BIT(channel % 8));
+
+		return 0;
+	case hwmon_in_input:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
+				       NCT6694_VIN_IDX(channel),
+				       sizeof(data->rpt->vin),
+				       &data->rpt->vin);
+		if (ret)
+			return ret;
+
+		*val = in_from_reg(data->rpt->vin);
+
+		return 0;
+	case hwmon_in_max:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		*val = in_from_reg(data->msg->hwmon_alarm.vin_limit[channel].hl);
+
+		return 0;
+	case hwmon_in_min:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		*val = in_from_reg(data->msg->hwmon_alarm.vin_limit[channel].ll);
+
+		return 0;
+	case hwmon_in_alarm:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
+				       NCT6694_VIN_STS(channel / 8),
+				       sizeof(data->rpt->status),
+				       &data->rpt->status);
+		if (ret)
+			return ret;
+
+		*val = !!(data->rpt->status & BIT(channel % 8));
+
+		return 0;
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_temp_read(struct device *dev, u32 attr, int channel,
+			     long *val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	unsigned char temp_en, temp_hyst;
+	signed char temp_max;
+	int ret, temp_raw;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_temp_enable:
+		temp_en = data->hwmon_en.tin_en[channel / 8];
+		*val = !!(temp_en & BIT(channel % 8));
+
+		return 0;
+	case hwmon_temp_input:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
+				       NCT6694_TIN_IDX(channel),
+				       sizeof(data->rpt->tin),
+				       &data->rpt->tin);
+		if (ret)
+			return ret;
+
+		temp_raw = data->rpt->tin.msb << 3;
+		temp_raw |= FIELD_GET(NCT6694_LSB_REG_MASK, data->rpt->tin.lsb);
+
+		/* Real temperature(milli degrees Celsius) = temp_raw * 1000 * 0.125 */
+		*val = sign_extend32(temp_raw, 10) * 125;
+
+		return 0;
+	case hwmon_temp_max:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		*val = temp_from_reg(data->msg->hwmon_alarm.tin_cfg[channel].hl);
+
+		return 0;
+	case hwmon_temp_max_hyst:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		temp_max = data->msg->hwmon_alarm.tin_cfg[channel].hl;
+		temp_hyst = FIELD_GET(NCT6694_TIN_HYST_MASK,
+				      data->msg->hwmon_alarm.tin_cfg[channel].hyst);
+		*val = temp_from_reg(temp_max - temp_hyst);
+
+		return 0;
+	case hwmon_temp_max_alarm:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
+				       NCT6694_TIN_STS(channel / 8),
+				       sizeof(data->rpt->status),
+				       &data->rpt->status);
+		if (ret)
+			return ret;
+
+		*val = !!(data->rpt->status & BIT(channel % 8));
+
+		return 0;
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_fan_read(struct device *dev, u32 attr, int channel,
+			    long *val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	unsigned char fanin_en;
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_fan_enable:
+		fanin_en = data->hwmon_en.fin_en[channel / 8];
+		*val = !!(fanin_en & BIT(channel % 8));
+
+		return 0;
+	case hwmon_fan_input:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
+				       NCT6694_FIN_IDX(channel),
+				       sizeof(data->rpt->fin),
+				       &data->rpt->fin);
+		if (ret)
+			return ret;
+
+		*val = be16_to_cpu(data->rpt->fin);
+
+		return 0;
+	case hwmon_fan_min:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		*val = be16_to_cpu(data->msg->hwmon_alarm.fin_ll[channel]);
+
+		return 0;
+	case hwmon_fan_min_alarm:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
+				       NCT6694_FIN_STS(channel / 8),
+				       sizeof(data->rpt->status),
+				       &data->rpt->status);
+		if (ret)
+			return ret;
+
+		*val = !!(data->rpt->status & BIT(channel % 8));
+
+		return 0;
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_pwm_read(struct device *dev, u32 attr, int channel,
+			    long *val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	unsigned char pwm_en;
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_pwm_enable:
+		pwm_en = data->hwmon_en.pwm_en[channel / 8];
+		*val = !!(pwm_en & BIT(channel % 8));
+
+		return 0;
+	case hwmon_pwm_input:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
+				       NCT6694_PWM_IDX(channel),
+				       sizeof(data->rpt->fin),
+				       &data->rpt->fin);
+		if (ret)
+			return ret;
+
+		*val = data->rpt->fin;
+
+		return 0;
+	case hwmon_pwm_freq:
+		*val = NCT6694_FREQ_FROM_REG(data->hwmon_en.pwm_freq[channel]);
+
+		return 0;
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_in_write(struct device *dev, u32 attr, int channel,
+			    long val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_in_enable:
+		if (val == 0)
+			data->hwmon_en.vin_en[channel / 8] &= ~BIT(channel % 8);
+		else if (val == 1)
+			data->hwmon_en.vin_en[channel / 8] |= BIT(channel % 8);
+		else
+			return -EINVAL;
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_CONTROL,
+					 sizeof(data->msg->hwmon_ctrl),
+					 &data->hwmon_en);
+	case hwmon_in_max:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		val = clamp_val(val, 0, 2032);
+		data->msg->hwmon_alarm.vin_limit[channel].hl = in_to_reg(val);
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_ALARM,
+					 sizeof(data->msg->hwmon_alarm),
+					 &data->msg->hwmon_alarm);
+	case hwmon_in_min:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		val = clamp_val(val, 0, 2032);
+		data->msg->hwmon_alarm.vin_limit[channel].ll = in_to_reg(val);
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_ALARM,
+					 sizeof(data->msg->hwmon_alarm),
+					 &data->msg->hwmon_alarm);
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_temp_write(struct device *dev, u32 attr, int channel,
+			      long val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	unsigned char temp_hyst;
+	signed char temp_max;
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_temp_enable:
+		if (val == 0)
+			data->hwmon_en.tin_en[channel / 8] &= ~BIT(channel % 8);
+		else if (val == 1)
+			data->hwmon_en.tin_en[channel / 8] |= BIT(channel % 8);
+		else
+			return -EINVAL;
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_CONTROL,
+					 sizeof(data->msg->hwmon_ctrl),
+					 &data->hwmon_en);
+	case hwmon_temp_max:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		val = clamp_val(val, -127000, 127000);
+		data->msg->hwmon_alarm.tin_cfg[channel].hl = temp_to_reg(val);
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_ALARM,
+					 sizeof(data->msg->hwmon_alarm),
+					 &data->msg->hwmon_alarm);
+	case hwmon_temp_max_hyst:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+
+		val = clamp_val(val, -127000, 127000);
+		temp_max = data->msg->hwmon_alarm.tin_cfg[channel].hl;
+		temp_hyst = temp_max - temp_to_reg(val);
+		temp_hyst = clamp_val(temp_hyst, 0, 7);
+		data->msg->hwmon_alarm.tin_cfg[channel].hyst =
+			(data->msg->hwmon_alarm.tin_cfg[channel].hyst & ~NCT6694_TIN_HYST_MASK) |
+			FIELD_PREP(NCT6694_TIN_HYST_MASK, temp_hyst);
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_ALARM,
+					 sizeof(data->msg->hwmon_alarm),
+					 &data->msg->hwmon_alarm);
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_fan_write(struct device *dev, u32 attr, int channel,
+			     long val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_fan_enable:
+		if (val == 0)
+			data->hwmon_en.fin_en[channel / 8] &= ~BIT(channel % 8);
+		else if (val == 1)
+			data->hwmon_en.fin_en[channel / 8] |= BIT(channel % 8);
+		else
+			return -EINVAL;
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_CONTROL,
+					 sizeof(data->msg->hwmon_ctrl),
+					 &data->hwmon_en);
+	case hwmon_fan_min:
+		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+				       NCT6694_HWMON_ALARM,
+				       sizeof(data->msg->hwmon_alarm),
+				       &data->msg->hwmon_alarm);
+		if (ret)
+			return ret;
+
+		val = clamp_val(val, 1, 65535);
+		data->msg->hwmon_alarm.fin_ll[channel] = (u16)cpu_to_be16(val);
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_ALARM,
+					 sizeof(data->msg->hwmon_alarm),
+					 &data->msg->hwmon_alarm);
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_pwm_write(struct device *dev, u32 attr, int channel,
+			     long val)
+{
+	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
+	int ret;
+
+	guard(mutex)(&data->lock);
+
+	switch (attr) {
+	case hwmon_pwm_enable:
+		if (val == 0)
+			data->hwmon_en.pwm_en[channel / 8] &= ~BIT(channel % 8);
+		else if (val == 1)
+			data->hwmon_en.pwm_en[channel / 8] |= BIT(channel % 8);
+		else
+			return -EINVAL;
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_CONTROL,
+					 sizeof(data->msg->hwmon_ctrl),
+					 &data->hwmon_en);
+	case hwmon_pwm_input:
+		if (val < 0 || val > 255)
+			return -EINVAL;
+
+		ret = nct6694_read_msg(data->nct6694, NCT6694_PWM_MOD,
+				       NCT6694_PWM_CONTROL,
+				       sizeof(data->msg->pwm_ctrl),
+				       &data->msg->pwm_ctrl);
+		if (ret)
+			return ret;
+
+		data->msg->pwm_ctrl.mal_val[channel] = val;
+
+		return nct6694_write_msg(data->nct6694, NCT6694_PWM_MOD,
+					 NCT6694_PWM_CONTROL,
+					 sizeof(data->msg->pwm_ctrl),
+					 &data->msg->pwm_ctrl);
+	case hwmon_pwm_freq:
+		data->hwmon_en.pwm_freq[channel] = NCT6694_FREQ_TO_REG(val);
+
+		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+					 NCT6694_HWMON_CONTROL,
+					 sizeof(data->msg->hwmon_ctrl),
+					 &data->hwmon_en);
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_read(struct device *dev, enum hwmon_sensor_types type,
+			u32 attr, int channel, long *val)
+{
+	switch (type) {
+	case hwmon_in:
+		/* in mV */
+		return nct6694_in_read(dev, attr, channel, val);
+	case hwmon_temp:
+		/* in mC */
+		return nct6694_temp_read(dev, attr, channel, val);
+	case hwmon_fan:
+		/* in RPM */
+		return nct6694_fan_read(dev, attr, channel, val);
+	case hwmon_pwm:
+		/* in value 0~255 */
+		return nct6694_pwm_read(dev, attr, channel, val);
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int nct6694_write(struct device *dev, enum hwmon_sensor_types type,
+			 u32 attr, int channel, long val)
+{
+	switch (type) {
+	case hwmon_in:
+		return nct6694_in_write(dev, attr, channel, val);
+	case hwmon_temp:
+		return nct6694_temp_write(dev, attr, channel, val);
+	case hwmon_fan:
+		return nct6694_fan_write(dev, attr, channel, val);
+	case hwmon_pwm:
+		return nct6694_pwm_write(dev, attr, channel, val);
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static umode_t nct6694_is_visible(const void *data,
+				  enum hwmon_sensor_types type,
+				  u32 attr, int channel)
+{
+	switch (type) {
+	case hwmon_in:
+		switch (attr) {
+		case hwmon_in_enable:
+		case hwmon_in_max:
+		case hwmon_in_min:
+			return 0644;
+		case hwmon_in_alarm:
+		case hwmon_in_input:
+			return 0444;
+		default:
+			return 0;
+		}
+	case hwmon_temp:
+		switch (attr) {
+		case hwmon_temp_enable:
+		case hwmon_temp_max:
+		case hwmon_temp_max_hyst:
+			return 0644;
+		case hwmon_temp_input:
+		case hwmon_temp_max_alarm:
+			return 0444;
+		default:
+			return 0;
+		}
+	case hwmon_fan:
+		switch (attr) {
+		case hwmon_fan_enable:
+		case hwmon_fan_min:
+			return 0644;
+		case hwmon_fan_input:
+		case hwmon_fan_min_alarm:
+			return 0444;
+		default:
+			return 0;
+		}
+	case hwmon_pwm:
+		switch (attr) {
+		case hwmon_pwm_enable:
+		case hwmon_pwm_freq:
+		case hwmon_pwm_input:
+			return 0644;
+		default:
+			return 0;
+		}
+	default:
+		return 0;
+	}
+}
+
+static const struct hwmon_ops nct6694_hwmon_ops = {
+	.is_visible = nct6694_is_visible,
+	.read = nct6694_read,
+	.write = nct6694_write,
+};
+
+static const struct hwmon_chip_info nct6694_chip_info = {
+	.ops = &nct6694_hwmon_ops,
+	.info = nct6694_info,
+};
+
+static int nct6694_hwmon_init(struct nct6694_hwmon_data *data)
+{
+	int ret;
+
+	/*
+	 * Record each Hardware Monitor Channel enable status
+	 * and PWM frequency register
+	 */
+	ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+			       NCT6694_HWMON_CONTROL,
+			       sizeof(data->msg->hwmon_ctrl),
+			       &data->hwmon_en);
+	if (ret)
+		return ret;
+
+	/* Select hwmon device alarm mode */
+	ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
+			       NCT6694_HWMON_ALARM,
+			       sizeof(data->msg->hwmon_alarm),
+			       &data->msg->hwmon_alarm);
+	if (ret)
+		return ret;
+
+	data->msg->hwmon_alarm.smi_ctrl = NCT6694_HWMON_REALTIME_IRQ;
+
+	return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
+				 NCT6694_HWMON_ALARM,
+				 sizeof(data->msg->hwmon_alarm),
+				 &data->msg->hwmon_alarm);
+}
+
+static int nct6694_hwmon_probe(struct platform_device *pdev)
+{
+	struct nct6694_hwmon_data *data;
+	struct nct6694 *nct6694 = dev_get_drvdata(pdev->dev.parent);
+	struct device *hwmon_dev;
+	int ret;
+
+	data = devm_kzalloc(&pdev->dev, sizeof(*data), GFP_KERNEL);
+	if (!data)
+		return -ENOMEM;
+
+	data->rpt = devm_kzalloc(&pdev->dev, sizeof(union nct6694_hwmon_rpt),
+				 GFP_KERNEL);
+	if (!data->rpt)
+		return -ENOMEM;
+
+	data->msg = devm_kzalloc(&pdev->dev, sizeof(union nct6694_hwmon_msg),
+				 GFP_KERNEL);
+	if (!data->msg)
+		return -ENOMEM;
+
+	data->nct6694 = nct6694;
+	devm_mutex_init(&pdev->dev, &data->lock);
+
+	ret = nct6694_hwmon_init(data);
+	if (ret)
+		return ret;
+
+	/* Register hwmon device to HWMON framework */
+	hwmon_dev = devm_hwmon_device_register_with_info(&pdev->dev,
+							 "nct6694", data,
+							 &nct6694_chip_info,
+							 NULL);
+	return PTR_ERR_OR_ZERO(hwmon_dev);
+}
+
+static struct platform_driver nct6694_hwmon_driver = {
+	.driver = {
+		.name	= "nct6694-hwmon",
+	},
+	.probe		= nct6694_hwmon_probe,
+};
+
+module_platform_driver(nct6694_hwmon_driver);
+
+MODULE_DESCRIPTION("USB-HWMON driver for NCT6694");
+MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:nct6694-hwmon");
-- 
2.34.1


^ permalink raw reply related	[flat|nested] 22+ messages in thread

* [PATCH v4 7/7] rtc: Add Nuvoton NCT6694 RTC support
  2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
                   ` (5 preceding siblings ...)
  2024-12-27  9:57 ` [PATCH v4 6/7] hwmon: Add Nuvoton NCT6694 HWMON support Ming Yu
@ 2024-12-27  9:57 ` Ming Yu
  2024-12-30 15:39   ` Alexandre Belloni
  6 siblings, 1 reply; 22+ messages in thread
From: Ming Yu @ 2024-12-27  9:57 UTC (permalink / raw)
  To: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, Ming Yu

This driver supports RTC functionality for NCT6694 MFD device
based on USB interface.

Signed-off-by: Ming Yu <a0282524688@gmail.com>
---
 MAINTAINERS               |   1 +
 drivers/rtc/Kconfig       |  10 ++
 drivers/rtc/Makefile      |   1 +
 drivers/rtc/rtc-nct6694.c | 263 ++++++++++++++++++++++++++++++++++++++
 4 files changed, 275 insertions(+)
 create mode 100644 drivers/rtc/rtc-nct6694.c

diff --git a/MAINTAINERS b/MAINTAINERS
index e5c65e382141..6a5164e42700 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -16731,6 +16731,7 @@ F:	drivers/hwmon/nct6694-hwmon.c
 F:	drivers/i2c/busses/i2c-nct6694.c
 F:	drivers/mfd/nct6694.c
 F:	drivers/net/can/nct6694_canfd.c
+F:	drivers/rtc/rtc-nct6694.c
 F:	drivers/watchdog/nct6694_wdt.c
 F:	include/linux/mfd/nct6694.h
 
diff --git a/drivers/rtc/Kconfig b/drivers/rtc/Kconfig
index a60bcc791a48..aeab67acbc84 100644
--- a/drivers/rtc/Kconfig
+++ b/drivers/rtc/Kconfig
@@ -416,6 +416,16 @@ config RTC_DRV_NCT3018Y
 	   This driver can also be built as a module, if so, the module will be
 	   called "rtc-nct3018y".
 
+config RTC_DRV_NCT6694
+	tristate "Nuvoton NCT6694 RTC support"
+	depends on MFD_NCT6694
+	help
+	  If you say yes to this option, support will be included for Nuvoton
+	  NCT6694, a USB device to RTC.
+
+	  This driver can also be built as a module. If so, the module will
+	  be called rtc-nct6694.
+
 config RTC_DRV_RK808
 	tristate "Rockchip RK805/RK808/RK809/RK817/RK818 RTC"
 	depends on MFD_RK8XX
diff --git a/drivers/rtc/Makefile b/drivers/rtc/Makefile
index 489b4ab07068..d0d6f4a4972e 100644
--- a/drivers/rtc/Makefile
+++ b/drivers/rtc/Makefile
@@ -118,6 +118,7 @@ obj-$(CONFIG_RTC_DRV_MXC)	+= rtc-mxc.o
 obj-$(CONFIG_RTC_DRV_MXC_V2)	+= rtc-mxc_v2.o
 obj-$(CONFIG_RTC_DRV_GAMECUBE)	+= rtc-gamecube.o
 obj-$(CONFIG_RTC_DRV_NCT3018Y)	+= rtc-nct3018y.o
+obj-$(CONFIG_RTC_DRV_NCT6694)	+= rtc-nct6694.o
 obj-$(CONFIG_RTC_DRV_NTXEC)	+= rtc-ntxec.o
 obj-$(CONFIG_RTC_DRV_OMAP)	+= rtc-omap.o
 obj-$(CONFIG_RTC_DRV_OPAL)	+= rtc-opal.o
diff --git a/drivers/rtc/rtc-nct6694.c b/drivers/rtc/rtc-nct6694.c
new file mode 100644
index 000000000000..9465ab895c6d
--- /dev/null
+++ b/drivers/rtc/rtc-nct6694.c
@@ -0,0 +1,263 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Nuvoton NCT6694 RTC driver based on USB interface.
+ *
+ * Copyright (C) 2024 Nuvoton Technology Corp.
+ */
+
+#include <linux/bcd.h>
+#include <linux/irqdomain.h>
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/nct6694.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/rtc.h>
+#include <linux/slab.h>
+
+/*
+ * USB command module type for NCT6694 RTC controller.
+ * This defines the module type used for communication with the NCT6694
+ * RTC controller over the USB interface.
+ */
+#define NCT6694_RTC_MOD		0x08
+
+/* Command 00h - RTC Time */
+#define NCT6694_RTC_TIME	0x0000	/* SEL|CMD */
+/* Command 01h - RTC Alarm */
+#define NCT6694_RTC_ALARM	0x0001	/* SEL|CMD */
+/* Command 02h - RTC Status */
+#define NCT6694_RTC_STATUS	0x0002	/* SEL|CMD */
+
+#define NCT6694_RTC_IRQ_INT_EN	BIT(0)	/* Transmit a USB INT-in when RTC alarm */
+#define NCT6694_RTC_IRQ_GPO_EN	BIT(5)	/* Trigger a GPO Low Pulse when RTC alarm */
+
+#define NCT6694_RTC_IRQ_EN	(NCT6694_RTC_IRQ_INT_EN | NCT6694_RTC_IRQ_GPO_EN)
+#define NCT6694_RTC_IRQ_STS	BIT(0)	/* Write 1 clear IRQ status */
+
+struct __packed nct6694_rtc_time {
+	u8 sec;
+	u8 min;
+	u8 hour;
+	u8 week;
+	u8 day;
+	u8 month;
+	u8 year;
+};
+
+struct __packed nct6694_rtc_alarm {
+	u8 sec;
+	u8 min;
+	u8 hour;
+	u8 alarm_en;
+	u8 alarm_pend;
+};
+
+struct __packed nct6694_rtc_status {
+	u8 irq_en;
+	u8 irq_pend;
+};
+
+union nct6694_rtc_msg {
+	struct nct6694_rtc_time time;
+	struct nct6694_rtc_alarm alarm;
+	struct nct6694_rtc_status sts;
+};
+
+struct nct6694_rtc_data {
+	struct nct6694 *nct6694;
+	struct rtc_device *rtc;
+	union nct6694_rtc_msg *msg;
+};
+
+static int nct6694_rtc_read_time(struct device *dev, struct rtc_time *tm)
+{
+	struct nct6694_rtc_data *data = dev_get_drvdata(dev);
+	struct nct6694_rtc_time *time = &data->msg->time;
+	int ret;
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_RTC_MOD,
+			       NCT6694_RTC_TIME,
+			       sizeof(*time),
+			       time);
+	if (ret)
+		return ret;
+
+	tm->tm_sec = bcd2bin(time->sec);                /* tm_sec expect 0 ~ 59 */
+	tm->tm_min = bcd2bin(time->min);                /* tm_min expect 0 ~ 59 */
+	tm->tm_hour = bcd2bin(time->hour);              /* tm_hour expect 0 ~ 23 */
+	tm->tm_wday = bcd2bin(time->week) - 1;          /* tm_wday expect 0 ~ 6 */
+	tm->tm_mday = bcd2bin(time->day);               /* tm_mday expect 1 ~ 31 */
+	tm->tm_mon = bcd2bin(time->month) - 1;          /* tm_month expect 0 ~ 11 */
+	tm->tm_year = bcd2bin(time->year) + 100;        /* tm_year expect since 1900 */
+
+	return ret;
+}
+
+static int nct6694_rtc_set_time(struct device *dev, struct rtc_time *tm)
+{
+	struct nct6694_rtc_data *data = dev_get_drvdata(dev);
+	struct nct6694_rtc_time *time = &data->msg->time;
+
+	time->sec = bin2bcd(tm->tm_sec);
+	time->min = bin2bcd(tm->tm_min);
+	time->hour = bin2bcd(tm->tm_hour);
+	time->week = bin2bcd(tm->tm_wday + 1);
+	time->day = bin2bcd(tm->tm_mday);
+	time->month = bin2bcd(tm->tm_mon + 1);
+	time->year = bin2bcd(tm->tm_year - 100);
+
+	return nct6694_write_msg(data->nct6694, NCT6694_RTC_MOD,
+				 NCT6694_RTC_TIME,
+				 sizeof(*time),
+				 time);
+}
+
+static int nct6694_rtc_read_alarm(struct device *dev, struct rtc_wkalrm *alrm)
+{
+	struct nct6694_rtc_data *data = dev_get_drvdata(dev);
+	struct nct6694_rtc_alarm *alarm = &data->msg->alarm;
+	int ret;
+
+	ret = nct6694_read_msg(data->nct6694, NCT6694_RTC_MOD,
+			       NCT6694_RTC_ALARM,
+			       sizeof(*alarm),
+			       alarm);
+	if (ret)
+		return ret;
+
+	alrm->time.tm_sec = bcd2bin(alarm->sec);
+	alrm->time.tm_min = bcd2bin(alarm->min);
+	alrm->time.tm_hour = bcd2bin(alarm->hour);
+	alrm->enabled = alarm->alarm_en;
+	alrm->pending = alarm->alarm_pend;
+
+	return ret;
+}
+
+static int nct6694_rtc_set_alarm(struct device *dev, struct rtc_wkalrm *alrm)
+{
+	struct nct6694_rtc_data *data = dev_get_drvdata(dev);
+	struct nct6694_rtc_alarm *alarm = &data->msg->alarm;
+
+	alarm->sec = bin2bcd(alrm->time.tm_sec);
+	alarm->min = bin2bcd(alrm->time.tm_min);
+	alarm->hour = bin2bcd(alrm->time.tm_hour);
+	alarm->alarm_en = alrm->enabled ? NCT6694_RTC_IRQ_EN : 0;
+	alarm->alarm_pend = 0;
+
+	return nct6694_write_msg(data->nct6694, NCT6694_RTC_MOD,
+				 NCT6694_RTC_ALARM,
+				 sizeof(*alarm),
+				 alarm);
+}
+
+static int nct6694_rtc_alarm_irq_enable(struct device *dev, unsigned int enabled)
+{
+	struct nct6694_rtc_data *data = dev_get_drvdata(dev);
+	struct nct6694_rtc_status *sts = &data->msg->sts;
+
+	if (enabled)
+		sts->irq_en |= NCT6694_RTC_IRQ_EN;
+	else
+		sts->irq_en &= ~NCT6694_RTC_IRQ_EN;
+
+	sts->irq_pend = 0;
+
+	return nct6694_write_msg(data->nct6694, NCT6694_RTC_MOD,
+				 NCT6694_RTC_STATUS,
+				 sizeof(*sts),
+				 sts);
+}
+
+static const struct rtc_class_ops nct6694_rtc_ops = {
+	.read_time = nct6694_rtc_read_time,
+	.set_time = nct6694_rtc_set_time,
+	.read_alarm = nct6694_rtc_read_alarm,
+	.set_alarm = nct6694_rtc_set_alarm,
+	.alarm_irq_enable = nct6694_rtc_alarm_irq_enable,
+};
+
+static irqreturn_t nct6694_irq(int irq, void *dev_id)
+{
+	struct nct6694_rtc_data *data = dev_id;
+	struct nct6694_rtc_status *sts = &data->msg->sts;
+	int ret;
+
+	rtc_lock(data->rtc);
+
+	sts->irq_en = NCT6694_RTC_IRQ_EN;
+	sts->irq_pend = NCT6694_RTC_IRQ_STS;
+	ret = nct6694_write_msg(data->nct6694, NCT6694_RTC_MOD,
+				NCT6694_RTC_STATUS,
+				sizeof(*sts),
+				sts);
+	if (ret) {
+		rtc_unlock(data->rtc);
+		return IRQ_NONE;
+	}
+
+	rtc_update_irq(data->rtc, 1, RTC_IRQF | RTC_AF);
+
+	rtc_unlock(data->rtc);
+
+	return IRQ_HANDLED;
+}
+
+static int nct6694_rtc_probe(struct platform_device *pdev)
+{
+	struct nct6694_rtc_data *data;
+	struct nct6694 *nct6694 = dev_get_drvdata(pdev->dev.parent);
+	int ret, irq;
+
+	irq = irq_create_mapping(nct6694->domain, NCT6694_IRQ_RTC);
+	if (!irq)
+		return -EINVAL;
+
+	data = devm_kzalloc(&pdev->dev, sizeof(*data), GFP_KERNEL);
+	if (!data)
+		return -ENOMEM;
+
+	data->msg = devm_kzalloc(&pdev->dev, sizeof(union nct6694_rtc_msg),
+				 GFP_KERNEL);
+	if (!data->msg)
+		return -ENOMEM;
+
+	data->rtc = devm_rtc_allocate_device(&pdev->dev);
+	if (IS_ERR(data->rtc))
+		return PTR_ERR(data->rtc);
+
+	data->nct6694 = nct6694;
+	data->rtc->ops = &nct6694_rtc_ops;
+	data->rtc->range_min = RTC_TIMESTAMP_BEGIN_2000;
+	data->rtc->range_max = RTC_TIMESTAMP_END_2099;
+
+	platform_set_drvdata(pdev, data);
+
+	ret = devm_request_threaded_irq(&pdev->dev, irq, NULL,
+					nct6694_irq, IRQF_ONESHOT,
+					"nct6694-rtc", data);
+	if (ret < 0)
+		return dev_err_probe(&pdev->dev, ret, "Failed to request irq\n");
+
+	ret = devm_rtc_register_device(data->rtc);
+	if (ret)
+		return dev_err_probe(&pdev->dev, ret, "Failed to register rtc\n");
+
+	device_init_wakeup(&pdev->dev, true);
+	return 0;
+}
+
+static struct platform_driver nct6694_rtc_driver = {
+	.driver = {
+		.name	= "nct6694-rtc",
+	},
+	.probe		= nct6694_rtc_probe,
+};
+
+module_platform_driver(nct6694_rtc_driver);
+
+MODULE_DESCRIPTION("USB-RTC driver for NCT6694");
+MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:nct6694-rtc");
-- 
2.34.1


^ permalink raw reply related	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694
  2024-12-27  9:57 ` [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694 Ming Yu
@ 2024-12-27 15:34   ` Vincent Mailhol
  2024-12-30  6:32     ` Ming Yu
  0 siblings, 1 reply; 22+ messages in thread
From: Vincent Mailhol @ 2024-12-27 15:34 UTC (permalink / raw)
  To: Ming Yu
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni, linux-usb

+cc: linux-usb@vger.kernel.org

On 27/12/2024 at 18:57, Ming Yu wrote:
> The Nuvoton NCT6694 is a peripheral expander with 16 GPIO chips,
> 6 I2C controllers, 2 CANfd controllers, 2 Watchdog timers, ADC,
> PWM, and RTC.
> 
> This driver implements USB device functionality and shares the
> chip's peripherals as a child device.
> 
> Each child device can use the USB functions nct6694_read_msg()
> and nct6694_write_msg() to issue a command. They can also request
> interrupt that will be called when the USB device receives its
> interrupt pipe.
> 
> Signed-off-by: Ming Yu <a0282524688@gmail.com>
> ---
>  MAINTAINERS                 |   7 +
>  drivers/mfd/Kconfig         |  10 +
>  drivers/mfd/Makefile        |   2 +
>  drivers/mfd/nct6694.c       | 394 ++++++++++++++++++++++++++++++++++++
>  include/linux/mfd/nct6694.h | 142 +++++++++++++
>  5 files changed, 555 insertions(+)
>  create mode 100644 drivers/mfd/nct6694.c
>  create mode 100644 include/linux/mfd/nct6694.h
> 
> diff --git a/MAINTAINERS b/MAINTAINERS
> index 910305c11e8a..acb270037642 100644
> --- a/MAINTAINERS
> +++ b/MAINTAINERS
> @@ -16722,6 +16722,13 @@ F:	drivers/nubus/
>  F:	include/linux/nubus.h
>  F:	include/uapi/linux/nubus.h
>  
> +NUVOTON NCT6694 MFD DRIVER
> +M:	Ming Yu <tmyu0@nuvoton.com>
> +L:	linux-kernel@vger.kernel.org
> +S:	Supported
> +F:	drivers/mfd/nct6694.c
> +F:	include/linux/mfd/nct6694.h
> +
>  NVIDIA (rivafb and nvidiafb) FRAMEBUFFER DRIVER
>  M:	Antonino Daplas <adaplas@gmail.com>
>  L:	linux-fbdev@vger.kernel.org
> diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
> index ae23b317a64e..5429ba97b457 100644
> --- a/drivers/mfd/Kconfig
> +++ b/drivers/mfd/Kconfig
> @@ -558,6 +558,16 @@ config MFD_MX25_TSADC
>  	  i.MX25 processors. They consist of a conversion queue for general
>  	  purpose ADC and a queue for Touchscreens.
>  
> +config MFD_NCT6694
> +	tristate "Nuvoton NCT6694 support"
> +	select MFD_CORE
> +	depends on USB
> +	help
> +	  This adds support for Nuvoton USB device NCT6694 sharing peripherals
> +	  This includes the USB devcie driver and core APIs.
                                ^^^^^^
device

> +	  Additional drivers must be enabled in order to use the functionality
> +	  of the device.
> +
>  config MFD_HI6421_PMIC
>  	tristate "HiSilicon Hi6421 PMU/Codec IC"
>  	depends on OF
> diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
> index e057d6d6faef..9d0365ba6a26 100644
> --- a/drivers/mfd/Makefile
> +++ b/drivers/mfd/Makefile
> @@ -117,6 +117,8 @@ obj-$(CONFIG_TWL6040_CORE)	+= twl6040.o
>  
>  obj-$(CONFIG_MFD_MX25_TSADC)	+= fsl-imx25-tsadc.o
>  
> +obj-$(CONFIG_MFD_NCT6694)	+= nct6694.o

Keep the alphabetic order. MFD_NCT6694 is after MFD_MC13XXX in the alphabet.

>  obj-$(CONFIG_MFD_MC13XXX)	+= mc13xxx-core.o
>  obj-$(CONFIG_MFD_MC13XXX_SPI)	+= mc13xxx-spi.o
>  obj-$(CONFIG_MFD_MC13XXX_I2C)	+= mc13xxx-i2c.o
> diff --git a/drivers/mfd/nct6694.c b/drivers/mfd/nct6694.c
> new file mode 100644
> index 000000000000..0f31489ef9fa
> --- /dev/null
> +++ b/drivers/mfd/nct6694.c

If I understand correctly, your device is an USB device, so shouldn't it
be under

  drivers/usb/mfd/nct6694.c

?

At the moment, I see no USB maintainers in CC (this is why I added
linux-usb myself). By putting it in the correct folder, the
get_maintainers.pl will give you the correct list of persons to put in copy.

The same comment applies to the other modules. For example, I would
expect to see the CAN module under:

  drivers/net/can/usb/nct6694_canfd.c

> @@ -0,0 +1,394 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * Nuvoton NCT6694 MFD driver based on USB interface.
> + *
> + * Copyright (C) 2024 Nuvoton Technology Corp.
> + */
> +
> +#include <linux/bits.h>
> +#include <linux/interrupt.h>
> +#include <linux/irq.h>
> +#include <linux/irqdomain.h>
> +#include <linux/kernel.h>
> +#include <linux/mfd/core.h>
> +#include <linux/mfd/nct6694.h>
> +#include <linux/module.h>
> +#include <linux/slab.h>
> +#include <linux/usb.h>
> +
> +#define MFD_DEV_SIMPLE(_name)				\
> +{							\
> +	.name = NCT6694_DEV_##_name,			\
> +}							\
> +
> +#define MFD_DEV_WITH_ID(_name, _id)			\
> +{							\
> +	.name = NCT6694_DEV_##_name,			\
> +	.id = _id,					\
> +}
> +
> +/* MFD device resources */
> +static const struct mfd_cell nct6694_dev[] = {
> +	MFD_DEV_WITH_ID(GPIO, 0x0),
> +	MFD_DEV_WITH_ID(GPIO, 0x1),
> +	MFD_DEV_WITH_ID(GPIO, 0x2),
> +	MFD_DEV_WITH_ID(GPIO, 0x3),
> +	MFD_DEV_WITH_ID(GPIO, 0x4),
> +	MFD_DEV_WITH_ID(GPIO, 0x5),
> +	MFD_DEV_WITH_ID(GPIO, 0x6),
> +	MFD_DEV_WITH_ID(GPIO, 0x7),
> +	MFD_DEV_WITH_ID(GPIO, 0x8),
> +	MFD_DEV_WITH_ID(GPIO, 0x9),
> +	MFD_DEV_WITH_ID(GPIO, 0xA),
> +	MFD_DEV_WITH_ID(GPIO, 0xB),
> +	MFD_DEV_WITH_ID(GPIO, 0xC),
> +	MFD_DEV_WITH_ID(GPIO, 0xD),
> +	MFD_DEV_WITH_ID(GPIO, 0xE),
> +	MFD_DEV_WITH_ID(GPIO, 0xF),
> +
> +	MFD_DEV_WITH_ID(I2C, 0x0),
> +	MFD_DEV_WITH_ID(I2C, 0x1),
> +	MFD_DEV_WITH_ID(I2C, 0x2),
> +	MFD_DEV_WITH_ID(I2C, 0x3),
> +	MFD_DEV_WITH_ID(I2C, 0x4),
> +	MFD_DEV_WITH_ID(I2C, 0x5),
> +
> +	MFD_DEV_WITH_ID(CAN, 0x0),
> +	MFD_DEV_WITH_ID(CAN, 0x1),
> +
> +	MFD_DEV_WITH_ID(WDT, 0x0),
> +	MFD_DEV_WITH_ID(WDT, 0x1),
> +
> +	MFD_DEV_SIMPLE(HWMON),
> +	MFD_DEV_SIMPLE(RTC),
> +};
> +
> +static int nct6694_response_err_handling(struct nct6694 *nct6694,
> +					 unsigned char err_status)
> +{
> +	struct device *dev = &nct6694->udev->dev;
> +
> +	switch (err_status) {
> +	case NCT6694_NO_ERROR:
> +		return err_status;
> +	case NCT6694_NOT_SUPPORT_ERROR:
> +		dev_dbg(dev, "%s: Command is not support!\n", __func__);

Grammar: Command is not supported

> +		break;
> +	case NCT6694_NO_RESPONSE_ERROR:
> +		dev_dbg(dev, "%s: Command is no response!\n", __func__);

Not sure what you meant here. Maybe: command didn't get a response? But
then, I do not see the nuance with the timeout.

> +		break;
> +	case NCT6694_TIMEOUT_ERROR:
> +		dev_dbg(dev, "%s: Command is timeout!\n", __func__);

Grammar: Command timed out
> +		break;
> +	case NCT6694_PENDING:
> +		dev_dbg(dev, "%s: Command is pending!\n", __func__);
> +		break;> +	default:
> +		return -EINVAL;
> +	}
> +
> +	return -EIO;
> +}
> +
> +int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
> +		     u16 length, void *buf)
> +{
> +	union nct6694_usb_msg *msg = nct6694->usb_msg;
> +	int tx_len, rx_len, ret;
> +
> +	guard(mutex)(&nct6694->access_lock);
> +
> +	memset(msg, 0, sizeof(*msg));
> +
> +	/* Send command packet to USB device */
> +	msg->cmd_header.mod = mod;
> +	msg->cmd_header.cmd = offset & 0xFF;
> +	msg->cmd_header.sel = (offset >> 8) & 0xFF;

In the other modules, you have some macros to combine together the cmd
and the sel (selector, I guess?). For example from nct6694_canfd.c:

  #define NCT6694_CAN_DELIVER(buf_cnt)	\
  	((((buf_cnt) & 0xFF) << 8) | 0x10)	/* CMD|SEL */

And here, you split them again. So what was the point to combine those
together in the first place?

Can't you just pass both the cmd and the sel as two separate argument?
Those cmd and sel concatenation macros are too confusing.

Also, if you are worried of having too many arguments in
nct6694_read_msg(), you may just directly pass a pointer to a struct
nct6694_cmd_header instead of all the arguments separately.

> +	msg->cmd_header.hctrl = NCT6694_HCTRL_GET;
> +	msg->cmd_header.len = cpu_to_le16(length);
> +
> +	ret = usb_bulk_msg(nct6694->udev,
> +			   usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
> +			   &msg->cmd_header, sizeof(*msg), &tx_len,
> +			   nct6694->timeout);
> +	if (ret)
> +		return ret;
> +
> +	/* Receive response packet from USB device */
> +	ret = usb_bulk_msg(nct6694->udev,
> +			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
> +			   &msg->response_header, sizeof(*msg), &rx_len,
> +			   nct6694->timeout);
> +	if (ret)
> +		return ret;
> +
> +	/* Receive data packet from USB device */
> +	ret = usb_bulk_msg(nct6694->udev,
> +			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
> +			   buf, NCT6694_MAX_PACKET_SZ, &rx_len, nct6694->timeout);
> +	if (ret)
> +		return ret;
> +
> +	if (rx_len != length) {
> +		dev_dbg(&nct6694->udev->dev, "%s: Received length is not match!\n",
> +			__func__);
> +		return -EIO;
> +	}
> +
> +	return nct6694_response_err_handling(nct6694, msg->response_header.sts);
> +}
> +EXPORT_SYMBOL(nct6694_read_msg);
> +
> +int nct6694_write_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
> +		      u16 length, void *buf)
> +{
> +	union nct6694_usb_msg *msg = nct6694->usb_msg;
> +	int tx_len, rx_len, ret;
> +
> +	guard(mutex)(&nct6694->access_lock);
> +
> +	memset(msg, 0, sizeof(*msg));
> +
> +	/* Send command packet to USB device */
> +	msg->cmd_header.mod = mod;
> +	msg->cmd_header.cmd = offset & 0xFF;
> +	msg->cmd_header.sel = (offset >> 8) & 0xFF;
> +	msg->cmd_header.hctrl = NCT6694_HCTRL_SET;
> +	msg->cmd_header.len = cpu_to_le16(length);
> +
> +	ret = usb_bulk_msg(nct6694->udev,
> +			   usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
> +			   &msg->cmd_header, sizeof(*msg), &tx_len,
> +			   nct6694->timeout);
> +	if (ret)
> +		return ret;
> +
> +	/* Send data packet to USB device */
> +	ret = usb_bulk_msg(nct6694->udev,
> +			   usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
> +			   buf, length, &tx_len, nct6694->timeout);
> +	if (ret)
> +		return ret;
> +
> +	/* Receive response packet from USB device */
> +	ret = usb_bulk_msg(nct6694->udev,
> +			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
> +			   &msg->response_header, sizeof(*msg), &rx_len,
> +			   nct6694->timeout);
> +	if (ret)
> +		return ret;
> +
> +	/* Receive data packet from USB device */
> +	ret = usb_bulk_msg(nct6694->udev,
> +			   usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
> +			   buf, NCT6694_MAX_PACKET_SZ, &rx_len, nct6694->timeout);

What if the object size of buf is smaller than NCT6694_MAX_PACKET_SZ?

> +	if (ret)
> +		return ret;
> +
> +	if (rx_len != length) {
> +		dev_dbg(&nct6694->udev->dev, "%s: Sent length is not match!\n",
> +			__func__);
> +		return -EIO;
> +	}
> +
> +	return nct6694_response_err_handling(nct6694, msg->response_header.sts);
> +}
> +EXPORT_SYMBOL(nct6694_write_msg);
> +
> +static void usb_int_callback(struct urb *urb)
> +{
> +	struct nct6694 *nct6694 = urb->context;
> +	struct device *dev = &nct6694->udev->dev;
> +	unsigned int *int_status = urb->transfer_buffer;
> +	int ret;
> +
> +	switch (urb->status) {
> +	case 0:
> +		break;
> +	case -ECONNRESET:
> +	case -ENOENT:
> +	case -ESHUTDOWN:
> +		return;
> +	default:
> +		goto resubmit;
> +	}
> +
> +	while (*int_status) {
> +		int irq = __ffs(*int_status);
> +
> +		generic_handle_irq_safe(irq_find_mapping(nct6694->domain, irq));
> +		*int_status &= ~BIT(irq);
> +	}
> +
> +resubmit:
> +	ret = usb_submit_urb(urb, GFP_ATOMIC);
> +	if (ret)
> +		dev_dbg(dev, "%s: Failed to resubmit urb, status %d",
> +			__func__, ret);

Print the error mnemotecnic instead of the error code:

  	dev_dbg(dev, "%s: Failed to resubmit urb, status %pe",
  		__func__, ERR_PTR(ret));

(apply to other location where you print error).

> +}
> +
> +static void nct6694_irq_lock(struct irq_data *data)
> +{
> +	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
> +
> +	mutex_lock(&nct6694->irq_lock);
> +}
> +
> +static void nct6694_irq_sync_unlock(struct irq_data *data)
> +{
> +	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
> +
> +	mutex_unlock(&nct6694->irq_lock);
> +}
> +
> +static void nct6694_irq_enable(struct irq_data *data)
> +{
> +	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
> +	irq_hw_number_t hwirq = irqd_to_hwirq(data);
> +
> +	nct6694->irq_enable |= BIT(hwirq);
> +}
> +
> +static void nct6694_irq_disable(struct irq_data *data)
> +{
> +	struct nct6694 *nct6694 = irq_data_get_irq_chip_data(data);
> +	irq_hw_number_t hwirq = irqd_to_hwirq(data);
> +
> +	nct6694->irq_enable &= ~BIT(hwirq);
> +}
> +
> +static struct irq_chip nct6694_irq_chip = {
> +	.name = "nct6694-irq",
> +	.flags = IRQCHIP_SKIP_SET_WAKE,
> +	.irq_bus_lock = nct6694_irq_lock,
> +	.irq_bus_sync_unlock = nct6694_irq_sync_unlock,
> +	.irq_enable = nct6694_irq_enable,
> +	.irq_disable = nct6694_irq_disable,
> +};
> +
> +static int nct6694_irq_domain_map(struct irq_domain *d, unsigned int irq,
> +				  irq_hw_number_t hw)
> +{
> +	struct nct6694 *nct6694 = d->host_data;
> +
> +	irq_set_chip_data(irq, nct6694);
> +	irq_set_chip_and_handler(irq, &nct6694_irq_chip, handle_simple_irq);
> +
> +	return 0;
> +}
> +
> +static void nct6694_irq_domain_unmap(struct irq_domain *d, unsigned int irq)
> +{
> +	irq_set_chip_and_handler(irq, NULL, NULL);
> +	irq_set_chip_data(irq, NULL);
> +}
> +
> +static const struct irq_domain_ops nct6694_irq_domain_ops = {
> +	.map	= nct6694_irq_domain_map,
> +	.unmap	= nct6694_irq_domain_unmap,
> +};
> +
> +static int nct6694_usb_probe(struct usb_interface *iface,
> +			     const struct usb_device_id *id)
> +{
> +	struct usb_device *udev = interface_to_usbdev(iface);
> +	struct usb_endpoint_descriptor *int_endpoint;
> +	struct usb_host_interface *interface;
> +	struct device *dev = &udev->dev;
> +	struct nct6694 *nct6694;
> +	int pipe, maxp;
> +	int ret;
> +
> +	interface = iface->cur_altsetting;
> +
> +	int_endpoint = &interface->endpoint[0].desc;
> +	if (!usb_endpoint_is_int_in(int_endpoint))
> +		return -ENODEV;
> +
> +	nct6694 = devm_kzalloc(dev, sizeof(*nct6694), GFP_KERNEL);
> +	if (!nct6694)
> +		return -ENOMEM;
> +
> +	pipe = usb_rcvintpipe(udev, NCT6694_INT_IN_EP);
> +	maxp = usb_maxpacket(udev, pipe);
> +
> +	nct6694->usb_msg = devm_kzalloc(dev, sizeof(union nct6694_usb_msg),
> +					GFP_KERNEL);
> +	if (!nct6694->usb_msg)
> +		return -ENOMEM;
> +
> +	nct6694->int_buffer = devm_kzalloc(dev, maxp, GFP_KERNEL);
> +	if (!nct6694->int_buffer)
> +		return -ENOMEM;
> +
> +	nct6694->int_in_urb = usb_alloc_urb(0, GFP_KERNEL);
> +	if (!nct6694->int_in_urb)
> +		return -ENOMEM;
> +
> +	nct6694->domain = irq_domain_add_simple(NULL, NCT6694_NR_IRQS, 0,
> +						&nct6694_irq_domain_ops,
> +						nct6694);
> +	if (!nct6694->domain) {
> +		ret = -ENODEV;
> +		goto err_urb;
> +	}
> +
> +	nct6694->udev = udev;
> +	nct6694->timeout = NCT6694_URB_TIMEOUT;	/* Wait until urb complete */
> +
> +	devm_mutex_init(dev, &nct6694->access_lock);
> +	devm_mutex_init(dev, &nct6694->irq_lock);
> +
> +	usb_fill_int_urb(nct6694->int_in_urb, udev, pipe,
> +			 nct6694->int_buffer, maxp, usb_int_callback,
> +			 nct6694, int_endpoint->bInterval);
> +	ret = usb_submit_urb(nct6694->int_in_urb, GFP_KERNEL);
> +	if (ret)
> +		goto err_urb;
> +
> +	dev_set_drvdata(dev, nct6694);
> +	usb_set_intfdata(iface, nct6694);
> +
> +	ret = mfd_add_hotplug_devices(dev, nct6694_dev, ARRAY_SIZE(nct6694_dev));
> +	if (ret)
> +		goto err_mfd;
> +
> +	return 0;
> +
> +err_mfd:
> +	usb_kill_urb(nct6694->int_in_urb);
> +err_urb:
> +	usb_free_urb(nct6694->int_in_urb);
> +	return ret;
> +}
> +
> +static void nct6694_usb_disconnect(struct usb_interface *iface)
> +{
> +	struct usb_device *udev = interface_to_usbdev(iface);
> +	struct nct6694 *nct6694 = usb_get_intfdata(iface);
> +
> +	mfd_remove_devices(&udev->dev);
> +	usb_kill_urb(nct6694->int_in_urb);
> +	usb_free_urb(nct6694->int_in_urb);
> +}
> +
> +static const struct usb_device_id nct6694_ids[] = {
> +	{ USB_DEVICE_AND_INTERFACE_INFO(NCT6694_VENDOR_ID,
> +					NCT6694_PRODUCT_ID,
> +					0xFF, 0x00, 0x00)},
> +	{}
> +};
> +MODULE_DEVICE_TABLE(usb, nct6694_ids);
> +
> +static struct usb_driver nct6694_usb_driver = {
> +	.name	= "nct6694",
> +	.id_table = nct6694_ids,
> +	.probe = nct6694_usb_probe,
> +	.disconnect = nct6694_usb_disconnect,
> +};
> +
> +module_usb_driver(nct6694_usb_driver);
> +
> +MODULE_DESCRIPTION("USB-MFD driver for NCT6694");
> +MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
> +MODULE_LICENSE("GPL");
> diff --git a/include/linux/mfd/nct6694.h b/include/linux/mfd/nct6694.h
> new file mode 100644
> index 000000000000..38c8c7af10d5
> --- /dev/null
> +++ b/include/linux/mfd/nct6694.h
> @@ -0,0 +1,142 @@
> +/* SPDX-License-Identifier: GPL-2.0 */
> +/*
> + * Nuvoton NCT6694 USB transaction and data structure.
> + *
> + * Copyright (C) 2024 Nuvoton Technology Corp.
> + */
> +
> +#ifndef __MFD_NCT6694_H
> +#define __MFD_NCT6694_H
> +
> +#define NCT6694_DEV_GPIO	"nct6694-gpio"
> +#define NCT6694_DEV_I2C		"nct6694-i2c"
> +#define NCT6694_DEV_CAN		"nct6694-can"
> +#define NCT6694_DEV_WDT		"nct6694-wdt"
> +#define NCT6694_DEV_HWMON	"nct6694-hwmon"
> +#define NCT6694_DEV_RTC		"nct6694-rtc"
> +
> +#define NCT6694_VENDOR_ID	0x0416
> +#define NCT6694_PRODUCT_ID	0x200B
> +#define NCT6694_INT_IN_EP	0x81
> +#define NCT6694_BULK_IN_EP	0x02
> +#define NCT6694_BULK_OUT_EP	0x03
> +#define NCT6694_MAX_PACKET_SZ	512
> +
> +#define NCT6694_HCTRL_SET	0x40
> +#define NCT6694_HCTRL_GET	0x80
> +
> +#define NCT6694_URB_TIMEOUT	1000
> +
> +enum nct6694_irq_id {
> +	NCT6694_IRQ_GPIO0 = 0,
> +	NCT6694_IRQ_GPIO1,
> +	NCT6694_IRQ_GPIO2,
> +	NCT6694_IRQ_GPIO3,
> +	NCT6694_IRQ_GPIO4,
> +	NCT6694_IRQ_GPIO5,
> +	NCT6694_IRQ_GPIO6,
> +	NCT6694_IRQ_GPIO7,
> +	NCT6694_IRQ_GPIO8,
> +	NCT6694_IRQ_GPIO9,
> +	NCT6694_IRQ_GPIOA,
> +	NCT6694_IRQ_GPIOB,
> +	NCT6694_IRQ_GPIOC,
> +	NCT6694_IRQ_GPIOD,
> +	NCT6694_IRQ_GPIOE,
> +	NCT6694_IRQ_GPIOF,
> +	NCT6694_IRQ_CAN1,
> +	NCT6694_IRQ_CAN2,
> +	NCT6694_IRQ_RTC,
> +	NCT6694_NR_IRQS,
> +};
> +
> +enum nct6694_response_err_status {
> +	NCT6694_NO_ERROR = 0,
> +	NCT6694_FORMAT_ERROR,
> +	NCT6694_RESERVED1,
> +	NCT6694_RESERVED2,
> +	NCT6694_NOT_SUPPORT_ERROR,
> +	NCT6694_NO_RESPONSE_ERROR,
> +	NCT6694_TIMEOUT_ERROR,
> +	NCT6694_PENDING,
> +};
> +
> +struct nct6694_cmd_header {
> +	u8 rsv1;
> +	u8 mod;
> +	u8 cmd;
> +	u8 sel;
> +	u8 hctrl;
> +	u8 rsv2;
> +	__le16 len;
> +} __packed;
> +
> +struct nct6694_response_header {
> +	u8 sequence_id;
> +	u8 sts;
> +	u8 reserved[4];
> +	__le16 len;
> +} __packed;
> +
> +union nct6694_usb_msg {
> +	struct nct6694_cmd_header cmd_header;
> +	struct nct6694_response_header response_header;
> +};
> +
> +struct nct6694 {
> +	struct usb_device *udev;
> +	struct urb *int_in_urb;
> +	struct irq_domain *domain;
> +	struct mutex access_lock;
> +	struct mutex irq_lock;
> +	union nct6694_usb_msg *usb_msg;
> +	unsigned char *int_buffer;
> +	unsigned int irq_enable;
> +	/* time in msec to wait for the urb to the complete */
> +	long timeout;
> +};
> +
> +/*
> + * nct6694_read_msg - Receive data from NCT6694 USB device
> + *
> + * @nct6694 - Nuvoton NCT6694 structure
> + * @mod - Module byte
> + * @offset - Offset byte or (Select byte | Command byte)
> + * @length - Length byte
> + * @buf - Read data from rx buffer
> + *
> + * USB Transaction format:
> + *
> + *	OUT	|RSV|MOD|CMD|SEL|HCTL|RSV|LEN_L|LEN_H|
> + *	OUT	|SEQ|STS|RSV|RSV|RSV|RSV||LEN_L|LEN_H|
> + *	IN	|-------D------A------D------A-------|
> + *	IN			......
> + *	IN	|-------D------A------D------A-------|

The structure already discribes this information pretty well. No need
for this table.

> + */
> +int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
> +		     u16 length, void *buf);
> +
> +/*
> + * nct6694_read_msg - Transmit data to NCT6694 USB device
> + *
> + * @nct6694 - Nuvoton NCT6694 structure
> + * @mod - Module byte
> + * @offset - Offset byte or (Select byte | Command byte)
> + * @length - Length byte
> + * @buf - Write data to tx buffer
> + *
> + * USB Transaction format:
> + *
> + *	OUT	|RSV|MOD|CMD|SEL|HCTL|RSV|LEN_L|LEN_H|
> + *	OUT	|-------D------A------D------A-------|
> + *	OUT			......
> + *	OUT	|-------D------A------D------A-------|
> + *	IN	|SEQ|STS|RSV|RSV|RSV|RSV||LEN_L|LEN_H|
> + *	IN	|-------D------A------D------A-------|
> + *	IN			......
> + *	IN	|-------D------A------D------A-------|
> + */
> +int nct6694_write_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
> +		      u16 length, void *buf);
> +
> +#endif

Yours sincerely,
Vincent Mailhol


^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support
  2024-12-27  9:57 ` [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support Ming Yu
@ 2024-12-27 15:59   ` Vincent Mailhol
  2025-01-02  5:25     ` Ming Yu
  2024-12-30  5:56   ` Vincent Mailhol
  1 sibling, 1 reply; 22+ messages in thread
From: Vincent Mailhol @ 2024-12-27 15:59 UTC (permalink / raw)
  To: Ming Yu
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni

On 27/12/2024 at 18:57, Ming Yu wrote:
> This driver supports Socket CANfd functionality for NCT6694 MFD
> device based on USB interface.
> 
> Signed-off-by: Ming Yu <a0282524688@gmail.com>
> ---
>  MAINTAINERS                     |   1 +
>  drivers/net/can/Kconfig         |  10 +
>  drivers/net/can/Makefile        |   1 +
>  drivers/net/can/nct6694_canfd.c | 826 ++++++++++++++++++++++++++++++++
>  4 files changed, 838 insertions(+)
>  create mode 100644 drivers/net/can/nct6694_canfd.c
> 
> diff --git a/MAINTAINERS b/MAINTAINERS
> index 5d63542233c4..b961c4827648 100644
> --- a/MAINTAINERS
> +++ b/MAINTAINERS
> @@ -16729,6 +16729,7 @@ S:	Supported
>  F:	drivers/gpio/gpio-nct6694.c
>  F:	drivers/i2c/busses/i2c-nct6694.c
>  F:	drivers/mfd/nct6694.c
> +F:	drivers/net/can/nct6694_canfd.c
>  F:	include/linux/mfd/nct6694.h
>  
>  NVIDIA (rivafb and nvidiafb) FRAMEBUFFER DRIVER
> diff --git a/drivers/net/can/Kconfig b/drivers/net/can/Kconfig
> index cf989bea9aa3..130e98ec28a5 100644
> --- a/drivers/net/can/Kconfig
> +++ b/drivers/net/can/Kconfig
> @@ -200,6 +200,16 @@ config CAN_SUN4I
>  	  To compile this driver as a module, choose M here: the module will
>  	  be called sun4i_can.
>  
> +config CAN_NCT6694
> +	tristate "Nuvoton NCT6694 Socket CANfd support"
> +	depends on MFD_NCT6694
> +	help
> +	  If you say yes to this option, support will be included for Nuvoton
> +	  NCT6694, a USB device to socket CANfd controller.
> +
> +	  This driver can also be built as a module. If so, the module will
> +	  be called nct6694_canfd.
> +
>  config CAN_TI_HECC
>  	depends on ARM
>  	tristate "TI High End CAN Controller"
> diff --git a/drivers/net/can/Makefile b/drivers/net/can/Makefile
> index a71db2cfe990..4a6b5b9d6c2b 100644
> --- a/drivers/net/can/Makefile
> +++ b/drivers/net/can/Makefile
> @@ -28,6 +28,7 @@ obj-$(CONFIG_CAN_JANZ_ICAN3)	+= janz-ican3.o
>  obj-$(CONFIG_CAN_KVASER_PCIEFD)	+= kvaser_pciefd.o
>  obj-$(CONFIG_CAN_MSCAN)		+= mscan/
>  obj-$(CONFIG_CAN_M_CAN)		+= m_can/
> +obj-$(CONFIG_CAN_NCT6694)	+= nct6694_canfd.o
>  obj-$(CONFIG_CAN_PEAK_PCIEFD)	+= peak_canfd/
>  obj-$(CONFIG_CAN_SJA1000)	+= sja1000/
>  obj-$(CONFIG_CAN_SUN4I)		+= sun4i_can.o
> diff --git a/drivers/net/can/nct6694_canfd.c b/drivers/net/can/nct6694_canfd.c
> new file mode 100644
> index 000000000000..94cfff288c14
> --- /dev/null
> +++ b/drivers/net/can/nct6694_canfd.c
> @@ -0,0 +1,826 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * Nuvoton NCT6694 Socket CANfd driver based on USB interface.
> + *
> + * Copyright (C) 2024 Nuvoton Technology Corp.
> + */
> +
> +#include <linux/can/dev.h>
> +#include <linux/can/rx-offload.h>
> +#include <linux/ethtool.h>
> +#include <linux/irqdomain.h>
> +#include <linux/kernel.h>
> +#include <linux/mfd/core.h>
> +#include <linux/mfd/nct6694.h>
> +#include <linux/module.h>
> +#include <linux/netdevice.h>
> +#include <linux/platform_device.h>
> +
> +#define DRVNAME "nct6694-can"
> +
> +/*
> + * USB command module type for NCT6694 CANfd controller.
> + * This defines the module type used for communication with the NCT6694
> + * CANfd controller over the USB interface.
> + */
> +#define NCT6694_CAN_MOD			0x05
> +
> +/* Command 00h - CAN Setting and Initialization */
> +#define NCT6694_CAN_SETTING(idx)	(idx ? 0x0100 : 0x0000)	/* CMD|SEL */
> +#define NCT6694_CAN_SETTING_CTRL1_MON	BIT(0)
> +#define NCT6694_CAN_SETTING_CTRL1_NISO	BIT(1)
> +#define NCT6694_CAN_SETTING_CTRL1_LBCK	BIT(2)
> +
> +/* Command 01h - CAN Information */
> +#define NCT6694_CAN_INFORMATION		0x0001	/* CMD|SEL */
> +
> +/* Command 02h - CAN Event */
> +#define NCT6694_CAN_EVENT(idx, mask)	\
> +	((((idx ? 0x80 : 0x00) |	\
> +	((mask) & 0xFF)) << 8) | 0x02)	/* CMD|SEL */
> +#define NCT6694_CAN_EVENT_ERR		BIT(0)
> +#define NCT6694_CAN_EVENT_STATUS	BIT(1)
> +#define NCT6694_CAN_EVENT_TX_EVT	BIT(2)
> +#define NCT6694_CAN_EVENT_RX_EVT	BIT(3)
> +#define NCT6694_CAN_EVENT_REC		BIT(4)
> +#define NCT6694_CAN_EVENT_TEC		BIT(5)
> +#define NCT6694_CAN_EVENT_MASK          GENMASK(3, 0)
> +#define NCT6694_CAN_EVT_TX_FIFO_EMPTY	BIT(7)	/* Read-clear */
> +#define NCT6694_CAN_EVT_RX_DATA_LOST	BIT(5)	/* Read-clear */
> +#define NCT6694_CAN_EVT_RX_HALF_FULL	BIT(6)	/* Read-clear */
> +#define NCT6694_CAN_EVT_RX_DATA_IN	BIT(7)	/* Read-clear*/
> +
> +/* Command 10h - CAN Deliver */
> +#define NCT6694_CAN_DELIVER(buf_cnt)	\
> +	((((buf_cnt) & 0xFF) << 8) | 0x10)	/* CMD|SEL */
> +
> +/* Command 11h - CAN Receive */
> +#define NCT6694_CAN_RECEIVE(idx, buf_cnt)	\
> +	((((idx ? 0x80 : 0x00) |		\
> +	((buf_cnt) & 0xFF)) << 8) | 0x11)	/* CMD|SEL */
> +
> +#define NCT6694_CAN_FRAME_TAG_CAN0	0xC0
> +#define NCT6694_CAN_FRAME_TAG_CAN1	0xC1
> +#define NCT6694_CAN_FRAME_FLAG_EFF	BIT(0)
> +#define NCT6694_CAN_FRAME_FLAG_RTR	BIT(1)
> +#define NCT6694_CAN_FRAME_FLAG_FD	BIT(2)
> +#define NCT6694_CAN_FRAME_FLAG_BRS	BIT(3)
> +#define NCT6694_CAN_FRAME_FLAG_ERR	BIT(4)
> +
> +#define NCT6694_NAPI_WEIGHT             32
> +
> +enum nct6694_event_err {
> +	NCT6694_CAN_EVT_ERR_NO_ERROR,
> +	NCT6694_CAN_EVT_ERR_CRC_ERROR,
> +	NCT6694_CAN_EVT_ERR_STUFF_ERROR,
> +	NCT6694_CAN_EVT_ERR_ACK_ERROR,
> +	NCT6694_CAN_EVT_ERR_FORM_ERROR,
> +	NCT6694_CAN_EVT_ERR_BIT_ERROR,
> +	NCT6694_CAN_EVT_ERR_TIMEOUT_ERROR,
> +	NCT6694_CAN_EVT_ERR_UNKNOWN_ERROR,
> +};
> +
> +enum nct6694_event_status {
> +	NCT6694_CAN_EVT_STS_ERROR_ACTIVE,
> +	NCT6694_CAN_EVT_STS_ERROR_PASSIVE,
> +	NCT6694_CAN_EVT_STS_BUS_OFF,
> +	NCT6694_CAN_EVT_STS_WARNING,
> +};
> +
> +struct __packed nct6694_can_setting {
> +	__le32 nbr;
> +	__le32 dbr;
> +	u8 active;
> +	u8 reserved[3];
> +	__le16 ctrl1;
> +	__le16 ctrl2;
> +	__le32 nbtp;
> +	__le32 dbtp;
> +};
> +
> +struct __packed nct6694_can_information {
> +	u8 tx_fifo_cnt;
> +	u8 rx_fifo_cnt;
> +	u8 reserved[2];
> +	__le32 can_clk;
> +};
> +
> +struct __packed nct6694_can_event_channel {
> +	u8 err;
> +	u8 status;
> +	u8 tx_evt;
> +	u8 rx_evt;
> +	u8 rec;
> +	u8 tec;
> +	u8 reserved[2];
> +};
> +
> +struct __packed nct6694_can_event {
> +	struct nct6694_can_event_channel evt_ch[2];
> +};

Remove this intermediate struct...

> +struct __packed nct6694_can_frame {
> +	u8 tag;
> +	u8 flag;
> +	u8 reserved;
> +	u8 length;
> +	__le32 id;
> +	u8 data[64];
> +};
> +
> +union nct6694_can_tx {
> +	struct nct6694_can_frame frame;
> +	struct nct6694_can_setting setting;
> +};
> +
> +union nct6694_can_rx {
> +	struct nct6694_can_event event;

... and instead, dircectly declare the array here:

  	struct nct6694_can_event event[2];

> +	struct nct6694_can_frame frame;
> +	struct nct6694_can_information info;
> +};
> +
> +struct nct6694_can_priv {
> +	struct can_priv can;	/* must be the first member */
> +	struct can_rx_offload offload;
> +	struct net_device *ndev;
> +	struct nct6694 *nct6694;
> +	struct mutex lock;
> +	struct sk_buff *tx_skb;
> +	struct workqueue_struct *wq;
> +	struct work_struct tx_work;
> +	union nct6694_can_tx *tx;
> +	union nct6694_can_rx *rx;
> +	unsigned char can_idx;
> +	bool tx_busy;

tx_busy is only set when the network queue is stopped, right? Isn't it
possible to use netif_tx_queue_stopped() instead of tx_busy?

> +};
> +
> +static inline struct nct6694_can_priv *rx_offload_to_priv(struct can_rx_offload *offload)
> +{
> +	return container_of(offload, struct nct6694_can_priv, offload);
> +}
> +
> +static const struct can_bittiming_const nct6694_can_bittiming_nominal_const = {
> +	.name = DRVNAME,
> +	.tseg1_min = 2,
> +	.tseg1_max = 256,
> +	.tseg2_min = 2,
> +	.tseg2_max = 128,
> +	.sjw_max = 128,
> +	.brp_min = 1,
> +	.brp_max = 511,
> +	.brp_inc = 1,
> +};
> +
> +static const struct can_bittiming_const nct6694_can_bittiming_data_const = {
> +	.name = DRVNAME,
> +	.tseg1_min = 1,
> +	.tseg1_max = 32,
> +	.tseg2_min = 1,
> +	.tseg2_max = 16,
> +	.sjw_max = 16,
> +	.brp_min = 1,
> +	.brp_max = 31,
> +	.brp_inc = 1,
> +};
> +
> +static void nct6694_can_rx_offload(struct can_rx_offload *offload,
> +				   struct sk_buff *skb)
> +{
> +	struct nct6694_can_priv *priv = rx_offload_to_priv(offload);
> +	int ret;
> +
> +	ret = can_rx_offload_queue_tail(offload, skb);
> +	if (ret)
> +		priv->ndev->stats.rx_fifo_errors++;
> +}
> +
> +static void nct6694_can_handle_lost_msg(struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct net_device_stats *stats = &ndev->stats;
> +	struct can_frame *cf;
> +	struct sk_buff *skb;
> +
> +	netdev_err(ndev, "RX FIFO overflow, message(s) lost.\n");
> +
> +	stats->rx_errors++;
> +	stats->rx_over_errors++;
> +
> +	skb = alloc_can_err_skb(ndev, &cf);
> +	if (!skb)
> +		return;
> +
> +	cf->can_id |= CAN_ERR_CRTL;
> +	cf->data[1] = CAN_ERR_CRTL_RX_OVERFLOW;
> +
> +	nct6694_can_rx_offload(&priv->offload, skb);
> +}
> +
> +static void nct6694_can_rx(struct net_device *ndev, u8 rx_evt)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct nct6694_can_frame *frame = &priv->rx->frame;
> +	struct canfd_frame *cfd;
> +	struct can_frame *cf;
> +	struct sk_buff *skb;
> +	int ret;
> +
> +	ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
> +			       NCT6694_CAN_RECEIVE(priv->can_idx, 1),
> +			       sizeof(*frame), frame);
> +	if (ret)
> +		return;
> +
> +	if (frame->flag & NCT6694_CAN_FRAME_FLAG_FD) {
> +		skb = alloc_canfd_skb(priv->ndev, &cfd);
> +		if (!skb)
> +			return;
> +
> +		cfd->can_id = le32_to_cpu(frame->id);
> +		cfd->len = frame->length;
> +		if (frame->flag & NCT6694_CAN_FRAME_FLAG_EFF)
> +			cfd->can_id |= CAN_EFF_FLAG;
> +		if (frame->flag & NCT6694_CAN_FRAME_FLAG_BRS)
> +			cfd->flags |= CANFD_BRS;
> +		if (frame->flag & NCT6694_CAN_FRAME_FLAG_ERR)
> +			cfd->flags |= CANFD_ESI;
> +
> +		memcpy(cfd->data, frame->data, cfd->len);
> +	} else {
> +		skb = alloc_can_skb(priv->ndev, &cf);
> +		if (!skb)
> +			return;
> +
> +		cf->can_id = le32_to_cpu(frame->id);
> +		cf->len = frame->length;
> +		if (frame->flag & NCT6694_CAN_FRAME_FLAG_EFF)
> +			cf->can_id |= CAN_EFF_FLAG;
> +		if (frame->flag & NCT6694_CAN_FRAME_FLAG_RTR)
> +			cf->can_id |= CAN_RTR_FLAG;
> +
> +		memcpy(cf->data, frame->data, cf->len);
> +	}
> +
> +	nct6694_can_rx_offload(&priv->offload, skb);
> +}
> +
> +static void nct6694_can_clean(struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +
> +	if (priv->tx_skb || priv->tx_busy)
> +		ndev->stats.tx_errors++;
> +	dev_kfree_skb(priv->tx_skb);
> +	if (priv->tx_busy)
> +		can_free_echo_skb(priv->ndev, 0, NULL);
> +	priv->tx_skb = NULL;
> +	priv->tx_busy = false;
> +}
> +
> +static int nct6694_can_get_berr_counter(const struct net_device *ndev,
> +					struct can_berr_counter *bec)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct nct6694_can_event *evt = &priv->rx->event;
> +	u8 mask = NCT6694_CAN_EVENT_REC | NCT6694_CAN_EVENT_TEC;
> +	int ret;
> +
> +	guard(mutex)(&priv->lock);
> +
> +	ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
> +			       NCT6694_CAN_EVENT(priv->can_idx, mask),
> +			       sizeof(*evt),
> +			       evt);
> +	if (ret < 0)
> +		return ret;
> +
> +	bec->rxerr = evt->evt_ch[priv->can_idx].rec;
> +	bec->txerr = evt->evt_ch[priv->can_idx].tec;
> +
> +	return 0;
> +}
> +
> +static void nct6694_can_handle_state_change(struct net_device *ndev,
> +					    u8 status)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	enum can_state new_state = priv->can.state;
> +	enum can_state rx_state, tx_state;
> +	struct can_berr_counter bec;
> +	struct can_frame *cf;
> +	struct sk_buff *skb;
> +
> +	nct6694_can_get_berr_counter(ndev, &bec);
> +	can_state_get_by_berr_counter(ndev, &bec, &tx_state, &rx_state);
> +
> +	if (status & NCT6694_CAN_EVT_STS_BUS_OFF)
> +		new_state = CAN_STATE_BUS_OFF;
> +	else if (status & NCT6694_CAN_EVT_STS_ERROR_PASSIVE)
> +		new_state = CAN_STATE_ERROR_PASSIVE;
> +	else if (status & NCT6694_CAN_EVT_STS_WARNING)
> +		new_state = CAN_STATE_ERROR_WARNING;
> +
> +	/* state hasn't changed */
> +	if (new_state == priv->can.state)
> +		return;
> +
> +	skb = alloc_can_err_skb(ndev, &cf);
> +
> +	tx_state = bec.txerr >= bec.rxerr ? new_state : 0;
> +	rx_state = bec.txerr <= bec.rxerr ? new_state : 0;
> +	can_change_state(ndev, cf, tx_state, rx_state);
> +
> +	if (new_state == CAN_STATE_BUS_OFF) {
> +		can_bus_off(ndev);
> +	} else if (skb) {
> +		cf->can_id |= CAN_ERR_CNT;
> +		cf->data[6] = bec.txerr;
> +		cf->data[7] = bec.rxerr;
> +	}
> +
> +	nct6694_can_rx_offload(&priv->offload, skb);
> +}
> +
> +static void nct6694_handle_bus_err(struct net_device *ndev, u8 bus_err)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct can_frame *cf;
> +	struct sk_buff *skb;
> +
> +	if (bus_err == NCT6694_CAN_EVT_ERR_NO_ERROR)
> +		return;
> +
> +	priv->can.can_stats.bus_error++;
> +
> +	skb = alloc_can_err_skb(ndev, &cf);
> +	if (skb)
> +		cf->can_id |= CAN_ERR_PROT | CAN_ERR_BUSERROR;
> +
> +	switch (bus_err) {
> +	case NCT6694_CAN_EVT_ERR_CRC_ERROR:
> +		netdev_dbg(ndev, "CRC error\n");
> +		ndev->stats.rx_errors++;
> +		if (skb)
> +			cf->data[3] |= CAN_ERR_PROT_LOC_CRC_SEQ;
> +		break;
> +
> +	case NCT6694_CAN_EVT_ERR_STUFF_ERROR:
> +		netdev_dbg(ndev, "Stuff error\n");
> +		ndev->stats.rx_errors++;
> +		if (skb)
> +			cf->data[2] |= CAN_ERR_PROT_STUFF;
> +		break;
> +
> +	case NCT6694_CAN_EVT_ERR_ACK_ERROR:
> +		netdev_dbg(ndev, "Ack error\n");
> +		ndev->stats.tx_errors++;
> +		if (skb) {
> +			cf->can_id |= CAN_ERR_ACK;
> +			cf->data[2] |= CAN_ERR_PROT_TX;
> +		}
> +		break;
> +
> +	case NCT6694_CAN_EVT_ERR_FORM_ERROR:
> +		netdev_dbg(ndev, "Form error\n");
> +		ndev->stats.rx_errors++;
> +		if (skb)
> +			cf->data[2] |= CAN_ERR_PROT_FORM;
> +		break;
> +
> +	case NCT6694_CAN_EVT_ERR_BIT_ERROR:
> +		netdev_dbg(ndev, "Bit error\n");
> +		ndev->stats.tx_errors++;
> +		if (skb)
> +			cf->data[2] |= CAN_ERR_PROT_TX | CAN_ERR_PROT_BIT;
> +		break;
> +
> +	default:
> +		break;
> +	}

Aren't you missing something here? You are populating a can frame but
you are returning without using it.

> +}
> +
> +static void nct6694_can_tx_irq(struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct net_device_stats *stats = &ndev->stats;
> +
> +	guard(mutex)(&priv->lock);
> +	stats->tx_bytes += can_get_echo_skb(ndev, 0, NULL);
> +	stats->tx_packets++;
> +	priv->tx_busy = false;
> +	netif_wake_queue(ndev);
> +}
> +
> +static irqreturn_t nct6694_can_irq(int irq, void *data)
> +{
> +	struct net_device *ndev = data;
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct nct6694_can_event *evt = &priv->rx->event;
> +	u8 tx_evt, rx_evt, bus_err, can_status;
> +	u8 mask_sts = NCT6694_CAN_EVENT_MASK;
> +	irqreturn_t handled = IRQ_NONE;
> +	int can_idx = priv->can_idx;
> +	int ret;
> +
> +	scoped_guard(mutex, &priv->lock) {
> +		ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
> +				       NCT6694_CAN_EVENT(can_idx, mask_sts),
> +				       sizeof(*evt), evt);
> +		if (ret < 0)
> +			return handled;
> +
> +		tx_evt = evt->evt_ch[can_idx].tx_evt;
> +		rx_evt = evt->evt_ch[can_idx].rx_evt;
> +		bus_err = evt->evt_ch[can_idx].err;
> +		can_status = evt->evt_ch[can_idx].status;
> +	}
> +
> +	if (rx_evt & NCT6694_CAN_EVT_RX_DATA_IN) {
> +		nct6694_can_rx(ndev, rx_evt);
> +		handled = IRQ_HANDLED;
> +	}
> +
> +	if (rx_evt & NCT6694_CAN_EVT_RX_DATA_LOST) {
> +		nct6694_can_handle_lost_msg(ndev);
> +		handled = IRQ_HANDLED;
> +	}
> +
> +	if (can_status) {
> +		nct6694_can_handle_state_change(ndev, can_status);
> +		handled = IRQ_HANDLED;
> +	}
> +
> +	if (priv->can.ctrlmode & CAN_CTRLMODE_BERR_REPORTING) {
> +		nct6694_handle_bus_err(ndev, bus_err);
> +		handled = IRQ_HANDLED;
> +	}
> +
> +	if (handled)
> +		can_rx_offload_threaded_irq_finish(&priv->offload);
> +
> +	if (tx_evt & NCT6694_CAN_EVT_TX_FIFO_EMPTY)
> +		nct6694_can_tx_irq(ndev);
> +
> +	return handled;
> +}
> +
> +static void nct6694_can_tx(struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct nct6694_can_frame *frame = &priv->tx->frame;
> +	struct net_device_stats *stats = &ndev->stats;
> +	struct sk_buff *skb = priv->tx_skb;
> +	struct canfd_frame *cfd;
> +	struct can_frame *cf;
> +	u32 txid;
> +	int err;
> +
> +	memset(frame, 0, sizeof(*frame));
> +
> +	if (priv->can_idx == 0)
> +		frame->tag = NCT6694_CAN_FRAME_TAG_CAN0;
> +	else
> +		frame->tag = NCT6694_CAN_FRAME_TAG_CAN1;
> +
> +	if (can_is_canfd_skb(skb)) {
> +		cfd = (struct canfd_frame *)priv->tx_skb->data;
> +
> +		if (cfd->flags & CANFD_BRS)
> +			frame->flag |= NCT6694_CAN_FRAME_FLAG_BRS;
> +
> +		if (cfd->can_id & CAN_EFF_FLAG) {
> +			txid = cfd->can_id & CAN_EFF_MASK;
> +			frame->flag |= NCT6694_CAN_FRAME_FLAG_EFF;
> +		} else {
> +			txid = cfd->can_id & CAN_SFF_MASK;
> +		}
> +		frame->flag |= NCT6694_CAN_FRAME_FLAG_FD;
> +		frame->id = cpu_to_le32(txid);
> +		frame->length = cfd->len;
> +
> +		memcpy(frame->data, cfd->data, cfd->len);
> +	} else {
> +		cf = (struct can_frame *)priv->tx_skb->data;
> +
> +		if (cf->can_id & CAN_RTR_FLAG)
> +			frame->flag |= NCT6694_CAN_FRAME_FLAG_RTR;
> +
> +		if (cf->can_id & CAN_EFF_FLAG) {
> +			txid = cf->can_id & CAN_EFF_MASK;
> +			frame->flag |= NCT6694_CAN_FRAME_FLAG_EFF;
> +		} else {
> +			txid = cf->can_id & CAN_SFF_MASK;
> +		}
> +		frame->id = cpu_to_le32(txid);
> +		frame->length = cf->len;
> +
> +		memcpy(frame->data, cf->data, cf->len);

Don't copy the payload if the frame is a remote frame.

> +		}
	^^^^^^^^

Bad indentation. Did you run script/checkpatch.pl before sending?

> +	err = nct6694_write_msg(priv->nct6694, NCT6694_CAN_MOD,
> +				NCT6694_CAN_DELIVER(1),
> +				sizeof(*frame),
> +				frame);
> +	if (err) {
> +		netdev_err(ndev, "%s: Tx FIFO full!\n", __func__);
> +		can_free_echo_skb(ndev, 0, NULL);
> +		stats->tx_dropped++;
> +		stats->tx_errors++;
> +		netif_wake_queue(ndev);
> +	}
> +}
> +
> +static void nct6694_can_tx_work(struct work_struct *work)
> +{
> +	struct nct6694_can_priv *priv = container_of(work,
> +						     struct nct6694_can_priv,
> +						     tx_work);
> +	struct net_device *ndev = priv->ndev;
> +
> +	guard(mutex)(&priv->lock);
> +
> +	if (priv->tx_skb) {
> +		if (priv->can.state == CAN_STATE_BUS_OFF) {
> +			nct6694_can_clean(ndev);
> +		} else {
> +			nct6694_can_tx(ndev);
> +			can_put_echo_skb(priv->tx_skb, ndev, 0, 0);
> +			priv->tx_busy = true;
> +			priv->tx_skb = NULL;
> +		}
> +	}
> +}
> +
> +static netdev_tx_t nct6694_can_start_xmit(struct sk_buff *skb,
> +					  struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +
> +	if (can_dev_dropped_skb(ndev, skb))
> +		return NETDEV_TX_OK;
> +
> +	if (priv->tx_skb || priv->tx_busy) {
> +		netdev_err(ndev, "hard_xmit called while tx busy\n");
> +		return NETDEV_TX_BUSY;
> +	}
> +
> +	netif_stop_queue(ndev);
> +	priv->tx_skb = skb;
> +	queue_work(priv->wq, &priv->tx_work);
> +
> +	return NETDEV_TX_OK;
> +}
> +
> +static int nct6694_can_start(struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	struct nct6694_can_setting *setting = &priv->tx->setting;
> +	const struct can_bittiming *n_bt = &priv->can.bittiming;
> +	const struct can_bittiming *d_bt = &priv->can.data_bittiming;
> +	int ret;
> +
> +	guard(mutex)(&priv->lock);
> +
> +	memset(setting, 0, sizeof(*setting));
> +	setting->nbr = cpu_to_le32(n_bt->bitrate);
> +	setting->dbr = cpu_to_le32(d_bt->bitrate);
> +
> +	if (priv->can.ctrlmode & CAN_CTRLMODE_LISTENONLY)
> +		setting->ctrl1 |= cpu_to_le16(NCT6694_CAN_SETTING_CTRL1_MON);
> +
> +	if ((priv->can.ctrlmode & CAN_CTRLMODE_FD) &&
> +	    priv->can.ctrlmode & CAN_CTRLMODE_FD_NON_ISO)
> +		setting->ctrl1 |= cpu_to_le16(NCT6694_CAN_SETTING_CTRL1_NISO);
> +
> +	if (priv->can.ctrlmode & CAN_CTRLMODE_LOOPBACK)
> +		setting->ctrl1 |= cpu_to_le16(NCT6694_CAN_SETTING_CTRL1_LBCK);
> +
> +	ret = nct6694_write_msg(priv->nct6694, NCT6694_CAN_MOD,
> +				NCT6694_CAN_SETTING(priv->can_idx),
> +				sizeof(*setting), setting);
> +	if (ret)
> +		return ret;
> +
> +	priv->can.state = CAN_STATE_ERROR_ACTIVE;
> +
> +	return ret;
> +}
> +
> +static int nct6694_can_stop(struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +
> +	netif_stop_queue(ndev);
> +	free_irq(ndev->irq, ndev);
> +	destroy_workqueue(priv->wq);
> +	priv->wq = NULL;
> +	nct6694_can_clean(ndev);
> +	priv->can.state = CAN_STATE_STOPPED;
> +	can_rx_offload_disable(&priv->offload);
> +	close_candev(ndev);
> +
> +	return 0;
> +}
> +
> +static int nct6694_can_set_mode(struct net_device *ndev, enum can_mode mode)
> +{
> +	switch (mode) {
> +	case CAN_MODE_START:
> +		nct6694_can_clean(ndev);
> +		nct6694_can_start(ndev);
> +		netif_wake_queue(ndev);
> +		break;

Nitpick: here, directly return 0...

> +	default:
> +		return -EOPNOTSUPP;
> +	}
> +
> +	return 0;

... and then remove that line.

> +}
> +
> +static int nct6694_can_open(struct net_device *ndev)
> +{
> +	struct nct6694_can_priv *priv = netdev_priv(ndev);
> +	int ret;
> +
> +	ret = open_candev(ndev);
> +	if (ret)
> +		return ret;
> +
> +	can_rx_offload_enable(&priv->offload);
> +
> +	ret = request_threaded_irq(ndev->irq, NULL,
> +				   nct6694_can_irq, IRQF_ONESHOT,
> +				   "nct6694_can", ndev);
> +	if (ret) {
> +		netdev_err(ndev, "Failed to request IRQ\n");
> +		goto close_candev;
> +	}
> +
> +	priv->wq = alloc_ordered_workqueue("%s-nct6694_wq",
> +					   WQ_FREEZABLE | WQ_MEM_RECLAIM,
> +					   ndev->name);
> +	if (!priv->wq) {
> +		ret = -ENOMEM;
> +		goto free_irq;
> +	}
> +
> +	priv->tx_skb = NULL;
> +	priv->tx_busy = false;
> +
> +	ret = nct6694_can_start(ndev);
> +	if (ret)
> +		goto destroy_wq;
> +
> +	netif_start_queue(ndev);
> +
> +	return 0;
> +
> +destroy_wq:
> +	destroy_workqueue(priv->wq);
> +free_irq:
> +	free_irq(ndev->irq, ndev);
> +close_candev:
> +	can_rx_offload_disable(&priv->offload);
> +	close_candev(ndev);
> +	return ret;
> +}
> +
> +static const struct net_device_ops nct6694_can_netdev_ops = {
> +	.ndo_open = nct6694_can_open,
> +	.ndo_stop = nct6694_can_stop,
> +	.ndo_start_xmit = nct6694_can_start_xmit,
> +	.ndo_change_mtu = can_change_mtu,
> +};
> +
> +static const struct ethtool_ops nct6694_can_ethtool_ops = {
> +	.get_ts_info = ethtool_op_get_ts_info,
> +};
> +
> +static int nct6694_can_get_clock(struct nct6694_can_priv *priv)
> +{
> +	struct nct6694_can_information *info = &priv->rx->info;
> +	int ret;
> +
> +	ret = nct6694_read_msg(priv->nct6694, NCT6694_CAN_MOD,
> +			       NCT6694_CAN_INFORMATION,
> +			       sizeof(*info),
> +			       info);
> +	if (ret)
> +		return ret;
> +
> +	return le32_to_cpu(info->can_clk);
> +}
> +
> +static int nct6694_can_probe(struct platform_device *pdev)
> +{
> +	const struct mfd_cell *cell = mfd_get_cell(pdev);
> +	struct nct6694 *nct6694 = dev_get_drvdata(pdev->dev.parent);
> +	struct nct6694_can_priv *priv;
> +	struct net_device *ndev;
> +	int ret, irq, can_clk;
> +
> +	irq = irq_create_mapping(nct6694->domain,
> +				 NCT6694_IRQ_CAN1 + cell->id);
> +	if (!irq)
> +		return irq;
> +
> +	ndev = alloc_candev(sizeof(struct nct6694_can_priv), 1);
> +	if (!ndev)
> +		return -ENOMEM;
> +
> +	ndev->irq = irq;
> +	ndev->flags |= IFF_ECHO;
> +	ndev->netdev_ops = &nct6694_can_netdev_ops;
> +	ndev->ethtool_ops = &nct6694_can_ethtool_ops;
> +
> +	priv = netdev_priv(ndev);
> +	priv->nct6694 = nct6694;
> +	priv->ndev = ndev;
> +
> +	priv->tx = devm_kzalloc(&pdev->dev, sizeof(union nct6694_can_tx),
> +				GFP_KERNEL);
> +	if (!priv->tx) {
> +		ret = -ENOMEM;
> +		goto free_candev;
> +	}
> +
> +	priv->rx = devm_kzalloc(&pdev->dev, sizeof(union nct6694_can_rx),
> +				GFP_KERNEL);
> +	if (!priv->rx) {
> +		ret = -ENOMEM;
> +		goto free_candev;
> +	}
> +
> +	can_clk = nct6694_can_get_clock(priv);
> +	if (can_clk < 0) {
> +		ret = dev_err_probe(&pdev->dev, can_clk,
> +				    "Failed to get clock\n");
> +		goto free_candev;
> +	}
> +
> +	devm_mutex_init(&pdev->dev, &priv->lock);
> +	INIT_WORK(&priv->tx_work, nct6694_can_tx_work);
> +
> +	priv->can_idx = cell->id;
> +	priv->can.state = CAN_STATE_STOPPED;
> +	priv->can.clock.freq = can_clk;
> +	priv->can.bittiming_const = &nct6694_can_bittiming_nominal_const;
> +	priv->can.data_bittiming_const = &nct6694_can_bittiming_data_const;
> +	priv->can.do_set_mode = nct6694_can_set_mode;
> +	priv->can.do_get_berr_counter = nct6694_can_get_berr_counter;
> +
> +	priv->can.ctrlmode = CAN_CTRLMODE_FD;
> +
> +	priv->can.ctrlmode_supported = CAN_CTRLMODE_LOOPBACK		|
> +				       CAN_CTRLMODE_LISTENONLY		|
> +				       CAN_CTRLMODE_FD			|
> +				       CAN_CTRLMODE_FD_NON_ISO		|
> +				       CAN_CTRLMODE_BERR_REPORTING;
> +
> +	ret = can_rx_offload_add_manual(ndev, &priv->offload,
> +					NCT6694_NAPI_WEIGHT);
> +	if (ret) {
> +		dev_err_probe(&pdev->dev, ret, "Failed to add rx_offload\n");
> +		goto free_candev;
> +	}
> +
> +	platform_set_drvdata(pdev, priv);
> +	SET_NETDEV_DEV(priv->ndev, &pdev->dev);
> +
> +	ret = register_candev(priv->ndev);
> +	if (ret)
> +		goto del_rx_offload;
> +
> +	return 0;
> +
> +del_rx_offload:
> +	can_rx_offload_del(&priv->offload);
> +free_candev:
> +	free_candev(ndev);
> +	return ret;
> +}
> +
> +static void nct6694_can_remove(struct platform_device *pdev)
> +{
> +	struct nct6694_can_priv *priv = platform_get_drvdata(pdev);
> +
> +	cancel_work_sync(&priv->tx_work);
> +	unregister_candev(priv->ndev);
> +	can_rx_offload_del(&priv->offload);
> +	free_candev(priv->ndev);
> +}
> +
> +static struct platform_driver nct6694_can_driver = {
> +	.driver = {
> +		.name	= DRVNAME,
> +	},
> +	.probe		= nct6694_can_probe,
> +	.remove		= nct6694_can_remove,
> +};
> +
> +module_platform_driver(nct6694_can_driver);
> +
> +MODULE_DESCRIPTION("USB-CAN FD driver for NCT6694");
> +MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
> +MODULE_LICENSE("GPL");
> +MODULE_ALIAS("platform:nct6694-can");


Yours sincerely,
Vincent Mailhol

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support
  2024-12-27  9:57 ` [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support Ming Yu
  2024-12-27 15:59   ` Vincent Mailhol
@ 2024-12-30  5:56   ` Vincent Mailhol
  2025-01-02  5:40     ` Ming Yu
  1 sibling, 1 reply; 22+ messages in thread
From: Vincent Mailhol @ 2024-12-30  5:56 UTC (permalink / raw)
  To: Ming Yu
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni

On 27/12/2024 at 18:57, Ming Yu wrote:
> This driver supports Socket CANfd functionality for NCT6694 MFD
> device based on USB interface.
> 
> Signed-off-by: Ming Yu <a0282524688@gmail.com>
> ---

(...)

> +config CAN_NCT6694
> +	tristate "Nuvoton NCT6694 Socket CANfd support"
> +	depends on MFD_NCT6694

I think it would be better to do a

	select MFD_NCT6694

here.

Then, make MFD_NCT6694 an hidden configuration in a similar fashion as
MFD_CORE. Alone, CONFIG_MFD_NCT6694 does nothing, so better to hide it
from the end user.

The comment also applies to the other patches.

> +	help
> +	  If you say yes to this option, support will be included for Nuvoton
> +	  NCT6694, a USB device to socket CANfd controller.
> +
> +	  This driver can also be built as a module. If so, the module will
> +	  be called nct6694_canfd.
> +

(...)

Yours sincerely,
Vincent Mailhol


^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694
  2024-12-27 15:34   ` Vincent Mailhol
@ 2024-12-30  6:32     ` Ming Yu
  2024-12-30  7:33       ` Vincent Mailhol
  0 siblings, 1 reply; 22+ messages in thread
From: Ming Yu @ 2024-12-30  6:32 UTC (permalink / raw)
  To: Vincent Mailhol
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni, linux-usb

Dear Vincent,

Thank you for your comments,

Vincent Mailhol <mailhol.vincent@wanadoo.fr> 於 2024年12月27日 週五 下午11:34寫道:
>
> +cc: linux-usb@vger.kernel.org
>
...
> > +config MFD_NCT6694
> > +     tristate "Nuvoton NCT6694 support"
> > +     select MFD_CORE
> > +     depends on USB
> > +     help
> > +       This adds support for Nuvoton USB device NCT6694 sharing peripherals
> > +       This includes the USB devcie driver and core APIs.
>                                 ^^^^^^
> device
>

Fix it in v5.

> > +       Additional drivers must be enabled in order to use the functionality
> > +       of the device.
> > +
> >  config MFD_HI6421_PMIC
> >       tristate "HiSilicon Hi6421 PMU/Codec IC"
> >       depends on OF
> > diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
> > index e057d6d6faef..9d0365ba6a26 100644
> > --- a/drivers/mfd/Makefile
> > +++ b/drivers/mfd/Makefile
> > @@ -117,6 +117,8 @@ obj-$(CONFIG_TWL6040_CORE)        += twl6040.o
> >
> >  obj-$(CONFIG_MFD_MX25_TSADC) += fsl-imx25-tsadc.o
> >
> > +obj-$(CONFIG_MFD_NCT6694)    += nct6694.o
>
> Keep the alphabetic order. MFD_NCT6694 is after MFD_MC13XXX in the alphabet.
>

Fix it in v5.

> >  obj-$(CONFIG_MFD_MC13XXX)    += mc13xxx-core.o
> >  obj-$(CONFIG_MFD_MC13XXX_SPI)        += mc13xxx-spi.o
> >  obj-$(CONFIG_MFD_MC13XXX_I2C)        += mc13xxx-i2c.o
> > diff --git a/drivers/mfd/nct6694.c b/drivers/mfd/nct6694.c
> > new file mode 100644
> > index 000000000000..0f31489ef9fa
> > --- /dev/null
> > +++ b/drivers/mfd/nct6694.c
>
> If I understand correctly, your device is an USB device, so shouldn't it
> be under
>
>   drivers/usb/mfd/nct6694.c
>
> ?

I understand, but there is no drivers/usb/mfd/ directory, I believe my
device is similar to dln2.c and viperboard.c, which is why I placed it
under drivers/mfd/

>
> At the moment, I see no USB maintainers in CC (this is why I added
> linux-usb myself). By putting it in the correct folder, the
> get_maintainers.pl will give you the correct list of persons to put in copy.
>

Okay, I will add CC to linux-usb from now on.

> The same comment applies to the other modules. For example, I would
> expect to see the CAN module under:
>
>   drivers/net/can/usb/nct6694_canfd.c
>

Understood! I will move the can driver to drivers/net/can/usb/ in v5.

...
> > +static int nct6694_response_err_handling(struct nct6694 *nct6694,
> > +                                      unsigned char err_status)
> > +{
> > +     struct device *dev = &nct6694->udev->dev;
> > +
> > +     switch (err_status) {
> > +     case NCT6694_NO_ERROR:
> > +             return err_status;
> > +     case NCT6694_NOT_SUPPORT_ERROR:
> > +             dev_dbg(dev, "%s: Command is not support!\n", __func__);
>
> Grammar: Command is not supported
>

Fix it in v5.

> > +             break;
> > +     case NCT6694_NO_RESPONSE_ERROR:
> > +             dev_dbg(dev, "%s: Command is no response!\n", __func__);
>
> Not sure what you meant here. Maybe: command didn't get a response? But
> then, I do not see the nuance with the timeout.
>

The firmware engine returns an error response.
If it returns NO_RESPONSE_ERROR, it means the target device did not
respond(e.g., I2C slave NACK).
If it returns TIMEOUT_ERROR, it means the engine process the command timed out.
I will add the comments to describe these error status in v5.

> > +             break;
> > +     case NCT6694_TIMEOUT_ERROR:
> > +             dev_dbg(dev, "%s: Command is timeout!\n", __func__);
>
> Grammar: Command timed out

Fix it in v5.

> > +             break;
> > +     case NCT6694_PENDING:
> > +             dev_dbg(dev, "%s: Command is pending!\n", __func__);
> > +             break;> +       default:
> > +             return -EINVAL;
> > +     }
> > +
> > +     return -EIO;
> > +}
> > +
> > +int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
> > +                  u16 length, void *buf)
> > +{
> > +     union nct6694_usb_msg *msg = nct6694->usb_msg;
> > +     int tx_len, rx_len, ret;
> > +
> > +     guard(mutex)(&nct6694->access_lock);
> > +
> > +     memset(msg, 0, sizeof(*msg));
> > +
> > +     /* Send command packet to USB device */
> > +     msg->cmd_header.mod = mod;
> > +     msg->cmd_header.cmd = offset & 0xFF;
> > +     msg->cmd_header.sel = (offset >> 8) & 0xFF;
>
> In the other modules, you have some macros to combine together the cmd
> and the sel (selector, I guess?). For example from nct6694_canfd.c:
>
>   #define NCT6694_CAN_DELIVER(buf_cnt)  \
>         ((((buf_cnt) & 0xFF) << 8) | 0x10)      /* CMD|SEL */
>
> And here, you split them again. So what was the point to combine those
> together in the first place?
>

Due to these two bytes may used to OFFSET in report channel for other
modules(gpio, hwmon), I will modify them below...

> Can't you just pass both the cmd and the sel as two separate argument?
> Those cmd and sel concatenation macros are too confusing.
>
> Also, if you are worried of having too many arguments in
> nct6694_read_msg(), you may just directly pass a pointer to a struct
> nct6694_cmd_header instead of all the arguments separately.
>

...
in mfd/nct6694.c
inline struct nct6694_cmd_header nct6694_init_cmd(u8 mod, u8 cmd, u8 sel,
                                                  u16 offset, u16 length)
{
        struct nct6694_cmd_header header;

        header.mod = mod;
        header.cmd = cmd;
        header.sel = sel;
        header.offset = cpu_to_le16(offset);
        header.len = cpu_to_le16(length);

        return header;
}
EXPORT_SYMBOL(nct6694_init_cmd);

int nct6694_read_msg(struct nct6694 *nct6694, struct nct6694_cmd_header *header,
                     void *buf)
{
        union nct6694_usb_msg *msg = nct6694->usb_msg;
        ...
        msg->cmd_header.mod = header->mod;
        msg->cmd_header.hctrl = NCT6694_HCTRL_GET;
        msg->cmd_header.len = header->len;
        if (msg->cmd_header.mod == 0xFF) {
                msg->cmd_header.offset = header->offset;
        } else {
                msg->cmd_header.cmd = header->cmd;
                msg->cmd_header.sel = header->sel;
        }
        ...
}
(also apply to nct6694_write_msg)

in other drivers, for example: gpio-nct6694.c
        struct nct6694_cmd_header cmd;
        int ret;

        guard(mutex)(&data->lock);

        cmd = nct6694_init_cmd(NCT6694_GPIO_MOD, 0, 0,
                               NCT6694_GPO_DIR + data->group,
                               sizeof(data->reg_val));

        ret = nct6694_read_msg(data->nct6694, &cmd, &data->reg_val);
        if (ret < 0)
                return ret;

Do you think this approach would be better?

> > +     msg->cmd_header.hctrl = NCT6694_HCTRL_GET;
> > +     msg->cmd_header.len = cpu_to_le16(length);
> > +
...
> > +int nct6694_write_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
> > +                   u16 length, void *buf)
> > +{
> > +     union nct6694_usb_msg *msg = nct6694->usb_msg;
> > +     int tx_len, rx_len, ret;
> > +
> > +     guard(mutex)(&nct6694->access_lock);
> > +
> > +     memset(msg, 0, sizeof(*msg));
> > +
> > +     /* Send command packet to USB device */
> > +     msg->cmd_header.mod = mod;
> > +     msg->cmd_header.cmd = offset & 0xFF;
> > +     msg->cmd_header.sel = (offset >> 8) & 0xFF;
> > +     msg->cmd_header.hctrl = NCT6694_HCTRL_SET;
> > +     msg->cmd_header.len = cpu_to_le16(length);
> > +
> > +     ret = usb_bulk_msg(nct6694->udev,
> > +                        usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
> > +                        &msg->cmd_header, sizeof(*msg), &tx_len,
> > +                        nct6694->timeout);
> > +     if (ret)
> > +             return ret;
> > +
> > +     /* Send data packet to USB device */
> > +     ret = usb_bulk_msg(nct6694->udev,
> > +                        usb_sndbulkpipe(nct6694->udev, NCT6694_BULK_OUT_EP),
> > +                        buf, length, &tx_len, nct6694->timeout);
> > +     if (ret)
> > +             return ret;
> > +
> > +     /* Receive response packet from USB device */
> > +     ret = usb_bulk_msg(nct6694->udev,
> > +                        usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
> > +                        &msg->response_header, sizeof(*msg), &rx_len,
> > +                        nct6694->timeout);
> > +     if (ret)
> > +             return ret;
> > +
> > +     /* Receive data packet from USB device */
> > +     ret = usb_bulk_msg(nct6694->udev,
> > +                        usb_rcvbulkpipe(nct6694->udev, NCT6694_BULK_IN_EP),
> > +                        buf, NCT6694_MAX_PACKET_SZ, &rx_len, nct6694->timeout);
>
> What if the object size of buf is smaller than NCT6694_MAX_PACKET_SZ?
>

I will fix it to le16_to_cpu(header->len) in the v5.

> > +     if (ret)
> > +             return ret;
> > +
> > +     if (rx_len != length) {
> > +             dev_dbg(&nct6694->udev->dev, "%s: Sent length is not match!\n",
> > +                     __func__);
> > +             return -EIO;
> > +     }
> > +
> > +     return nct6694_response_err_handling(nct6694, msg->response_header.sts);
> > +}
> > +EXPORT_SYMBOL(nct6694_write_msg);
> > +
> > +static void usb_int_callback(struct urb *urb)
> > +{
> > +     struct nct6694 *nct6694 = urb->context;
> > +     struct device *dev = &nct6694->udev->dev;
> > +     unsigned int *int_status = urb->transfer_buffer;
> > +     int ret;
> > +
> > +     switch (urb->status) {
> > +     case 0:
> > +             break;
> > +     case -ECONNRESET:
> > +     case -ENOENT:
> > +     case -ESHUTDOWN:
> > +             return;
> > +     default:
> > +             goto resubmit;
> > +     }
> > +
> > +     while (*int_status) {
> > +             int irq = __ffs(*int_status);
> > +
> > +             generic_handle_irq_safe(irq_find_mapping(nct6694->domain, irq));
> > +             *int_status &= ~BIT(irq);
> > +     }
> > +
> > +resubmit:
> > +     ret = usb_submit_urb(urb, GFP_ATOMIC);
> > +     if (ret)
> > +             dev_dbg(dev, "%s: Failed to resubmit urb, status %d",
> > +                     __func__, ret);
>
> Print the error mnemotecnic instead of the error code:
>
>         dev_dbg(dev, "%s: Failed to resubmit urb, status %pe",
>                 __func__, ERR_PTR(ret));
>
> (apply to other location where you print error).
>

Understood. Fix these in v5.

> > +}
> > +
...
> > + * nct6694_read_msg - Receive data from NCT6694 USB device
> > + *
> > + * @nct6694 - Nuvoton NCT6694 structure
> > + * @mod - Module byte
> > + * @offset - Offset byte or (Select byte | Command byte)
> > + * @length - Length byte
> > + * @buf - Read data from rx buffer
> > + *
> > + * USB Transaction format:
> > + *
> > + *   OUT     |RSV|MOD|CMD|SEL|HCTL|RSV|LEN_L|LEN_H|
> > + *   OUT     |SEQ|STS|RSV|RSV|RSV|RSV||LEN_L|LEN_H|
> > + *   IN      |-------D------A------D------A-------|
> > + *   IN                      ......
> > + *   IN      |-------D------A------D------A-------|
>
> The structure already discribes this information pretty well. No need
> for this table.
>

Drop it in v5.

> > + */

Best regards,
Ming

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694
  2024-12-30  6:32     ` Ming Yu
@ 2024-12-30  7:33       ` Vincent Mailhol
  2024-12-30  8:47         ` Ming Yu
  0 siblings, 1 reply; 22+ messages in thread
From: Vincent Mailhol @ 2024-12-30  7:33 UTC (permalink / raw)
  To: Ming Yu
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni, linux-usb

On 30/12/2024 at 15:32, Ming Yu wrote:
> Dear Vincent,
> 
> Thank you for your comments,
> 
> Vincent Mailhol <mailhol.vincent@wanadoo.fr> 於 2024年12月27日 週五 下午11:34寫道:

(...)

>>>  obj-$(CONFIG_MFD_MC13XXX)    += mc13xxx-core.o
>>>  obj-$(CONFIG_MFD_MC13XXX_SPI)        += mc13xxx-spi.o
>>>  obj-$(CONFIG_MFD_MC13XXX_I2C)        += mc13xxx-i2c.o
>>> diff --git a/drivers/mfd/nct6694.c b/drivers/mfd/nct6694.c
>>> new file mode 100644
>>> index 000000000000..0f31489ef9fa
>>> --- /dev/null
>>> +++ b/drivers/mfd/nct6694.c
>>
>> If I understand correctly, your device is an USB device, so shouldn't it
>> be under
>>
>>   drivers/usb/mfd/nct6694.c
>>
>> ?
> 
> I understand, but there is no drivers/usb/mfd/ directory, I believe my
> device is similar to dln2.c and viperboard.c, which is why I placed it
> under drivers/mfd/

Well, at the end, this is not my tree. Maybe I am saying something silly
here? I am fine to defer this problem to the more relevant people. If
the maintainers from the linux-usb mailing list are happy like you did,
then so am I.

>> At the moment, I see no USB maintainers in CC (this is why I added
>> linux-usb myself). By putting it in the correct folder, the
>> get_maintainers.pl will give you the correct list of persons to put in copy.
>>
> 
> Okay, I will add CC to linux-usb from now on.

Ack.

>> The same comment applies to the other modules. For example, I would
>> expect to see the CAN module under:
>>
>>   drivers/net/can/usb/nct6694_canfd.c
>>
> 
> Understood! I will move the can driver to drivers/net/can/usb/ in v5.

Ack.

(...)

>>> +int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
>>> +                  u16 length, void *buf)
>>> +{
>>> +     union nct6694_usb_msg *msg = nct6694->usb_msg;
>>> +     int tx_len, rx_len, ret;
>>> +
>>> +     guard(mutex)(&nct6694->access_lock);
>>> +
>>> +     memset(msg, 0, sizeof(*msg));
>>> +
>>> +     /* Send command packet to USB device */
>>> +     msg->cmd_header.mod = mod;
>>> +     msg->cmd_header.cmd = offset & 0xFF;
>>> +     msg->cmd_header.sel = (offset >> 8) & 0xFF;
>>
>> In the other modules, you have some macros to combine together the cmd
>> and the sel (selector, I guess?). For example from nct6694_canfd.c:
>>
>>   #define NCT6694_CAN_DELIVER(buf_cnt)  \
>>         ((((buf_cnt) & 0xFF) << 8) | 0x10)      /* CMD|SEL */
>>
>> And here, you split them again. So what was the point to combine those
>> together in the first place?
>>
> 
> Due to these two bytes may used to OFFSET in report channel for other
> modules(gpio, hwmon), I will modify them below...
> 
>> Can't you just pass both the cmd and the sel as two separate argument?
>> Those cmd and sel concatenation macros are too confusing.
>>
>> Also, if you are worried of having too many arguments in
>> nct6694_read_msg(), you may just directly pass a pointer to a struct
>> nct6694_cmd_header instead of all the arguments separately.
>>
> 
> ...
> in mfd/nct6694.c
> inline struct nct6694_cmd_header nct6694_init_cmd(u8 mod, u8 cmd, u8 sel,
>                                                   u16 offset, u16 length)
> {
>         struct nct6694_cmd_header header;
> 
>         header.mod = mod;
>         header.cmd = cmd;
>         header.sel = sel;
>         header.offset = cpu_to_le16(offset);

I am not sure how this is supposed to work. If the both the offset and
the cmd/sel pair occupies the same slot in memory, then the offset would
just overwrite what you just put in the cmd and sel fields.

>         header.len = cpu_to_le16(length);
> 
>         return header;
> }
> EXPORT_SYMBOL(nct6694_init_cmd);
> 
> int nct6694_read_msg(struct nct6694 *nct6694, struct nct6694_cmd_header *header,
>                      void *buf)
> {
>         union nct6694_usb_msg *msg = nct6694->usb_msg;
>         ...
>         msg->cmd_header.mod = header->mod;
>         msg->cmd_header.hctrl = NCT6694_HCTRL_GET;
>         msg->cmd_header.len = header->len;
>         if (msg->cmd_header.mod == 0xFF) {
>                 msg->cmd_header.offset = header->offset;
>         } else {
>                 msg->cmd_header.cmd = header->cmd;
>                 msg->cmd_header.sel = header->sel;
>         }
>         ...
> }
> (also apply to nct6694_write_msg)
> 
> in other drivers, for example: gpio-nct6694.c
>         struct nct6694_cmd_header cmd;
>         int ret;
> 
>         guard(mutex)(&data->lock);
> 
>         cmd = nct6694_init_cmd(NCT6694_GPIO_MOD, 0, 0,
>                                NCT6694_GPO_DIR + data->group,
>                                sizeof(data->reg_val));
> 
>         ret = nct6694_read_msg(data->nct6694, &cmd, &data->reg_val);
>         if (ret < 0)
>                 return ret;
> 
> Do you think this approach would be better?

If the two bytes may be used separately or in combination, then I think
it is better to describe this in your structure. Something like this:

  struct nct6694_cmd_header {
  	u8 rsv1;
  	u8 mod;
  	union {
  		__le16 offset;
  		struct {
  			u8 cmd;
  			u8 sel;
  		}; __packed
  	} __packed;
  	u8 hctrl;
  	u8 rsv2;
  	__le16 len;
  } __packed;

Then, your prototype becomes:

  int nct6694_read_msg(struct nct6694 *nct6694,
  		       struct nct6694_cmd_header *cmd_hd,
  		       void *buf)

If the caller needs to pass an offset:

  void foo(struct nct6694 *nct6694, u8 mod, u16 offset, u16 length)
  {
  	struct nct6694_cmd_header cmd_hd = { 0 };

  	cmd_hd.mod = mod;
  	cmd_hd.offset = cpu_to_le16(offset);
  	cmd_hd.len = cpu_to_le16(length);

  	nct6694_read_msg(nct6694, &cmd_hd, NULL);
  }

If the caller needs to pass a cmd and sel pair:

  void foo(struct nct6694 *nct6694, u8 mod, u8 cmd, u8 sel, u16 length)
  {
  	struct nct6694_cmd_header cmd_hd = { 0 };

  	cmd_hd.mod = mod;
  	cmd_hd.cmd = cmd;
  	cmd_hd.sel = sel;
  	cmd_hd.len = cpu_to_le16(length);

  	nct6694_read_msg(nct6694, &cmd_hd, NULL);
  }

This way, no more cmd and sel concatenation/deconcatenation and no
conditional if/else logic.

cmd_hd.hctrl (and other similar fields which are common to everyone) may
be set in nct6694_read_msg().

(...)


Yours sincerely,
Vincent Mailhol


^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694
  2024-12-30  7:33       ` Vincent Mailhol
@ 2024-12-30  8:47         ` Ming Yu
  2024-12-30  9:38           ` Vincent Mailhol
  0 siblings, 1 reply; 22+ messages in thread
From: Ming Yu @ 2024-12-30  8:47 UTC (permalink / raw)
  To: Vincent Mailhol
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni, linux-usb

Vincent Mailhol <mailhol.vincent@wanadoo.fr> 於 2024年12月30日 週一 下午3:34寫道:
>
...
> >> If I understand correctly, your device is an USB device, so shouldn't it
> >> be under
> >>
> >>   drivers/usb/mfd/nct6694.c
> >>
> >> ?
> >
> > I understand, but there is no drivers/usb/mfd/ directory, I believe my
> > device is similar to dln2.c and viperboard.c, which is why I placed it
> > under drivers/mfd/
>
> Well, at the end, this is not my tree. Maybe I am saying something silly
> here? I am fine to defer this problem to the more relevant people. If
> the maintainers from the linux-usb mailing list are happy like you did,
> then so am I.
>

Understood.

> >> At the moment, I see no USB maintainers in CC (this is why I added
> >> linux-usb myself). By putting it in the correct folder, the
> >> get_maintainers.pl will give you the correct list of persons to put in copy.
> >>
> >
> > Okay, I will add CC to linux-usb from now on.
>
> Ack.
>
> >> The same comment applies to the other modules. For example, I would
> >> expect to see the CAN module under:
> >>
> >>   drivers/net/can/usb/nct6694_canfd.c
> >>
> >
> > Understood! I will move the can driver to drivers/net/can/usb/ in v5.
>
> Ack.
>
> (...)
>
> >>> +int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u16 offset,
> >>> +                  u16 length, void *buf)
> >>> +{
...
>
> If the two bytes may be used separately or in combination, then I think
> it is better to describe this in your structure. Something like this:
>
>   struct nct6694_cmd_header {
>         u8 rsv1;
>         u8 mod;
>         union {
>                 __le16 offset;
>                 struct {
>                         u8 cmd;
>                         u8 sel;
>                 }; __packed
>         } __packed;
>         u8 hctrl;
>         u8 rsv2;
>         __le16 len;
>   } __packed;
>

Sorry for forgetting to list the structure in last mail, but the
revised structure is same as yours.

> Then, your prototype becomes:
>
>   int nct6694_read_msg(struct nct6694 *nct6694,
>                        struct nct6694_cmd_header *cmd_hd,
>                        void *buf)
>
> If the caller needs to pass an offset:
>
>   void foo(struct nct6694 *nct6694, u8 mod, u16 offset, u16 length)
>   {
>         struct nct6694_cmd_header cmd_hd = { 0 };
>
>         cmd_hd.mod = mod;
>         cmd_hd.offset = cpu_to_le16(offset);
>         cmd_hd.len = cpu_to_le16(length);
>
>         nct6694_read_msg(nct6694, &cmd_hd, NULL);
>   }
>
> If the caller needs to pass a cmd and sel pair:
>
>   void foo(struct nct6694 *nct6694, u8 mod, u8 cmd, u8 sel, u16 length)
>   {
>         struct nct6694_cmd_header cmd_hd = { 0 };
>
>         cmd_hd.mod = mod;
>         cmd_hd.cmd = cmd;
>         cmd_hd.sel = sel;
>         cmd_hd.len = cpu_to_le16(length);
>
>         nct6694_read_msg(nct6694, &cmd_hd, NULL);
>   }
>
> This way, no more cmd and sel concatenation/deconcatenation and no
> conditional if/else logic.
>
> cmd_hd.hctrl (and other similar fields which are common to everyone) may
> be set in nct6694_read_msg().
>

Understood, that means I need to export these four function, right?
  - int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u8 cmd,
                         u8 sel, u16 length, void *buf);
  - int nct6694_read_rpt(struct nct6694 *nct6694, u8 mod, u16 offset,
                         u16 length, void *buf);
  - int nct6694_write_msg(struct nct6694 *nct6694, u8 mod, u8 cmd,
                          u8 sel, u16 length, void *buf);
  - int nct6694_write_rpt(struct nct6694 *nct6694, u8 mod, u16 offset,
                          u16 length, void *buf);

Both nct6694_read_msg() and nct6694_read_rpt() call
nct6694_read(struct nct6694 *nct6694, struct nct6694_cmd_header
cmd_hd, void *buf),
then nct6694_write_msg() and nct6694_write_rpt() call
nct6694_write(struct nct6694 *nct6694, struct nct6694_cmd_header
cmd_hd, void *buf).
(nct6694_read/nct6694_write is origin nct6694_read_msg/nct6694_write_msg)


Thanks,
Ming

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694
  2024-12-30  8:47         ` Ming Yu
@ 2024-12-30  9:38           ` Vincent Mailhol
  0 siblings, 0 replies; 22+ messages in thread
From: Vincent Mailhol @ 2024-12-30  9:38 UTC (permalink / raw)
  To: Ming Yu
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni, linux-usb

On 30/12/2024 at 17:47, Ming Yu wrote:
> Vincent Mailhol <mailhol.vincent@wanadoo.fr> 於 2024年12月30日 週一 下午3:34寫道:

(...)

>> If the two bytes may be used separately or in combination, then I think
>> it is better to describe this in your structure. Something like this:
>>
>>   struct nct6694_cmd_header {
>>         u8 rsv1;
>>         u8 mod;
>>         union {
>>                 __le16 offset;
>>                 struct {
>>                         u8 cmd;
>>                         u8 sel;
>>                 }; __packed
>>         } __packed;
>>         u8 hctrl;
>>         u8 rsv2;
>>         __le16 len;
>>   } __packed;
>>
> 
> Sorry for forgetting to list the structure in last mail, but the
> revised structure is same as yours.
> 
>> Then, your prototype becomes:
>>
>>   int nct6694_read_msg(struct nct6694 *nct6694,
>>                        struct nct6694_cmd_header *cmd_hd,
>>                        void *buf)
>>
>> If the caller needs to pass an offset:
>>
>>   void foo(struct nct6694 *nct6694, u8 mod, u16 offset, u16 length)
>>   {
>>         struct nct6694_cmd_header cmd_hd = { 0 };
>>
>>         cmd_hd.mod = mod;
>>         cmd_hd.offset = cpu_to_le16(offset);
>>         cmd_hd.len = cpu_to_le16(length);
>>
>>         nct6694_read_msg(nct6694, &cmd_hd, NULL);
>>   }
>>
>> If the caller needs to pass a cmd and sel pair:
>>
>>   void foo(struct nct6694 *nct6694, u8 mod, u8 cmd, u8 sel, u16 length)
>>   {
>>         struct nct6694_cmd_header cmd_hd = { 0 };
>>
>>         cmd_hd.mod = mod;
>>         cmd_hd.cmd = cmd;
>>         cmd_hd.sel = sel;
>>         cmd_hd.len = cpu_to_le16(length);
>>
>>         nct6694_read_msg(nct6694, &cmd_hd, NULL);
>>   }
>>
>> This way, no more cmd and sel concatenation/deconcatenation and no
>> conditional if/else logic.
>>
>> cmd_hd.hctrl (and other similar fields which are common to everyone) may
>> be set in nct6694_read_msg().
>>
> 
> Understood, that means I need to export these four function, right?
>   - int nct6694_read_msg(struct nct6694 *nct6694, u8 mod, u8 cmd,
>                          u8 sel, u16 length, void *buf);
>   - int nct6694_read_rpt(struct nct6694 *nct6694, u8 mod, u16 offset,
>                          u16 length, void *buf);
>   - int nct6694_write_msg(struct nct6694 *nct6694, u8 mod, u8 cmd,
>                           u8 sel, u16 length, void *buf);
>   - int nct6694_write_rpt(struct nct6694 *nct6694, u8 mod, u16 offset,
>                           u16 length, void *buf);
> 
> Both nct6694_read_msg() and nct6694_read_rpt() call
> nct6694_read(struct nct6694 *nct6694, struct nct6694_cmd_header
> cmd_hd, void *buf),
> then nct6694_write_msg() and nct6694_write_rpt() call
> nct6694_write(struct nct6694 *nct6694, struct nct6694_cmd_header
> cmd_hd, void *buf).
> (nct6694_read/nct6694_write is origin nct6694_read_msg/nct6694_write_msg)

I was more thinking of exposing:

  int nct6694_read_msg(struct nct6694 *nct6694,
  		       struct nct6694_cmd_header *cmd_hd,
  		       void *buf);

and:

  int nct6694_write_msg(struct nct6694 *nct6694,
  			struct nct6694_cmd_header *cmd_hd,
  			void *buf);

and then the different modules fill the cmd_hd argument themselves and
directly call one of those two functions with no intermediaries.

But your solution is also acceptable. The core issue is the artificial
packing and depacking of the cmd and sel pair. As long as this core
issue is resolved and as long as the ugly concatenation macro can be
removed, I think it is OK. Choose the approach you prefer :)


Yours sincerely,
Vincent Mailhol

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 7/7] rtc: Add Nuvoton NCT6694 RTC support
  2024-12-27  9:57 ` [PATCH v4 7/7] rtc: Add Nuvoton NCT6694 RTC support Ming Yu
@ 2024-12-30 15:39   ` Alexandre Belloni
  0 siblings, 0 replies; 22+ messages in thread
From: Alexandre Belloni @ 2024-12-30 15:39 UTC (permalink / raw)
  To: Ming Yu
  Cc: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc

On 27/12/2024 17:57:27+0800, Ming Yu wrote:
> +	ret = devm_rtc_register_device(data->rtc);
> +	if (ret)
> +		return dev_err_probe(&pdev->dev, ret, "Failed to register rtc\n");

There is no error path where the error is silent in
devm_rtc_register_device, the message is unnecessary .

> +
> +	device_init_wakeup(&pdev->dev, true);
> +	return 0;
> +}
> +
> +static struct platform_driver nct6694_rtc_driver = {
> +	.driver = {
> +		.name	= "nct6694-rtc",
> +	},
> +	.probe		= nct6694_rtc_probe,
> +};
> +
> +module_platform_driver(nct6694_rtc_driver);
> +
> +MODULE_DESCRIPTION("USB-RTC driver for NCT6694");
> +MODULE_AUTHOR("Ming Yu <tmyu0@nuvoton.com>");
> +MODULE_LICENSE("GPL");
> +MODULE_ALIAS("platform:nct6694-rtc");
> -- 
> 2.34.1
> 

-- 
Alexandre Belloni, co-owner and COO, Bootlin
Embedded Linux and Kernel engineering
https://bootlin.com

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support
  2024-12-27 15:59   ` Vincent Mailhol
@ 2025-01-02  5:25     ` Ming Yu
  0 siblings, 0 replies; 22+ messages in thread
From: Ming Yu @ 2025-01-02  5:25 UTC (permalink / raw)
  To: Vincent Mailhol
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni

Dear Vincent,

Thank you for your comments,

Vincent Mailhol <mailhol.vincent@wanadoo.fr> 於 2024年12月27日 週五 下午11:59寫道:
>
> > +
> > +struct __packed nct6694_can_event_channel {
> > +     u8 err;
> > +     u8 status;
> > +     u8 tx_evt;
> > +     u8 rx_evt;
> > +     u8 rec;
> > +     u8 tec;
> > +     u8 reserved[2];
> > +};
> > +
> > +struct __packed nct6694_can_event {
> > +     struct nct6694_can_event_channel evt_ch[2];
> > +};
>
> Remove this intermediate struct...
>
> > +struct __packed nct6694_can_frame {
> > +     u8 tag;
> > +     u8 flag;
> > +     u8 reserved;
> > +     u8 length;
> > +     __le32 id;
> > +     u8 data[64];
> > +};
> > +
> > +union nct6694_can_tx {
> > +     struct nct6694_can_frame frame;
> > +     struct nct6694_can_setting setting;
> > +};
> > +
> > +union nct6694_can_rx {
> > +     struct nct6694_can_event event;
>
> ... and instead, dircectly declare the array here:
>
>         struct nct6694_can_event event[2];
>

Okay! Fix it in v5.

> > +     struct nct6694_can_frame frame;
> > +     struct nct6694_can_information info;
> > +};
> > +
> > +struct nct6694_can_priv {
> > +     struct can_priv can;    /* must be the first member */
> > +     struct can_rx_offload offload;
> > +     struct net_device *ndev;
> > +     struct nct6694 *nct6694;
> > +     struct mutex lock;
> > +     struct sk_buff *tx_skb;
> > +     struct workqueue_struct *wq;
> > +     struct work_struct tx_work;
> > +     union nct6694_can_tx *tx;
> > +     union nct6694_can_rx *rx;
> > +     unsigned char can_idx;
> > +     bool tx_busy;
>
> tx_busy is only set when the network queue is stopped, right? Isn't it
> possible to use netif_tx_queue_stopped() instead of tx_busy?
>

Yes, I'll make the modification in v5.

> > +};
> > +
...
> > +static void nct6694_can_handle_state_change(struct net_device *ndev,
> > +                                         u8 status)
> > +{
> > +     struct nct6694_can_priv *priv = netdev_priv(ndev);
> > +     enum can_state new_state = priv->can.state;
> > +     enum can_state rx_state, tx_state;
> > +     struct can_berr_counter bec;
> > +     struct can_frame *cf;
> > +     struct sk_buff *skb;
> > +
> > +     nct6694_can_get_berr_counter(ndev, &bec);
> > +     can_state_get_by_berr_counter(ndev, &bec, &tx_state, &rx_state);
> > +
> > +     if (status & NCT6694_CAN_EVT_STS_BUS_OFF)
> > +             new_state = CAN_STATE_BUS_OFF;
> > +     else if (status & NCT6694_CAN_EVT_STS_ERROR_PASSIVE)
> > +             new_state = CAN_STATE_ERROR_PASSIVE;
> > +     else if (status & NCT6694_CAN_EVT_STS_WARNING)
> > +             new_state = CAN_STATE_ERROR_WARNING;

The procedure for handling state changes is incorrect. I'll fix it in
the next patch.
(e.g.)
switch (status) {
case NCT6694_CAN_EVT_STS_BUS_OFF):
    new_state = CAN_STATE_BUS_OFFF;
    break;
...
}

> > +
> > +     /* state hasn't changed */
> > +     if (new_state == priv->can.state)
> > +             return;
> > +
> > +     skb = alloc_can_err_skb(ndev, &cf);
> > +
> > +     tx_state = bec.txerr >= bec.rxerr ? new_state : 0;
> > +     rx_state = bec.txerr <= bec.rxerr ? new_state : 0;
> > +     can_change_state(ndev, cf, tx_state, rx_state);
> > +
> > +     if (new_state == CAN_STATE_BUS_OFF) {
> > +             can_bus_off(ndev);
> > +     } else if (skb) {
> > +             cf->can_id |= CAN_ERR_CNT;
> > +             cf->data[6] = bec.txerr;
> > +             cf->data[7] = bec.rxerr;
> > +     }
> > +
> > +     nct6694_can_rx_offload(&priv->offload, skb);
> > +}
> > +
> > +static void nct6694_handle_bus_err(struct net_device *ndev, u8 bus_err)
> > +{
> > +     struct nct6694_can_priv *priv = netdev_priv(ndev);
> > +     struct can_frame *cf;
> > +     struct sk_buff *skb;
> > +
> > +     if (bus_err == NCT6694_CAN_EVT_ERR_NO_ERROR)
> > +             return;
> > +
> > +     priv->can.can_stats.bus_error++;
> > +
> > +     skb = alloc_can_err_skb(ndev, &cf);
> > +     if (skb)
> > +             cf->can_id |= CAN_ERR_PROT | CAN_ERR_BUSERROR;
> > +
> > +     switch (bus_err) {
> > +     case NCT6694_CAN_EVT_ERR_CRC_ERROR:
> > +             netdev_dbg(ndev, "CRC error\n");
> > +             ndev->stats.rx_errors++;
> > +             if (skb)
> > +                     cf->data[3] |= CAN_ERR_PROT_LOC_CRC_SEQ;
> > +             break;
> > +
> > +     case NCT6694_CAN_EVT_ERR_STUFF_ERROR:
> > +             netdev_dbg(ndev, "Stuff error\n");
> > +             ndev->stats.rx_errors++;
> > +             if (skb)
> > +                     cf->data[2] |= CAN_ERR_PROT_STUFF;
> > +             break;
> > +
> > +     case NCT6694_CAN_EVT_ERR_ACK_ERROR:
> > +             netdev_dbg(ndev, "Ack error\n");
> > +             ndev->stats.tx_errors++;
> > +             if (skb) {
> > +                     cf->can_id |= CAN_ERR_ACK;
> > +                     cf->data[2] |= CAN_ERR_PROT_TX;
> > +             }
> > +             break;
> > +
> > +     case NCT6694_CAN_EVT_ERR_FORM_ERROR:
> > +             netdev_dbg(ndev, "Form error\n");
> > +             ndev->stats.rx_errors++;
> > +             if (skb)
> > +                     cf->data[2] |= CAN_ERR_PROT_FORM;
> > +             break;
> > +
> > +     case NCT6694_CAN_EVT_ERR_BIT_ERROR:
> > +             netdev_dbg(ndev, "Bit error\n");
> > +             ndev->stats.tx_errors++;
> > +             if (skb)
> > +                     cf->data[2] |= CAN_ERR_PROT_TX | CAN_ERR_PROT_BIT;
> > +             break;
> > +
> > +     default:
> > +             break;
> > +     }
>
> Aren't you missing something here? You are populating a can frame but
> you are returning without using it.
>

Sorry for forgetting to process rx offload function, I'll add
nct6694_can_rx_offload() here in the v5.

> > +}
> > +
...
> > +static void nct6694_can_tx(struct net_device *ndev)
> > +{
> > +     struct nct6694_can_priv *priv = netdev_priv(ndev);
> > +     struct nct6694_can_frame *frame = &priv->tx->frame;
> > +     struct net_device_stats *stats = &ndev->stats;
> > +     struct sk_buff *skb = priv->tx_skb;
> > +     struct canfd_frame *cfd;
> > +     struct can_frame *cf;
> > +     u32 txid;
> > +     int err;
> > +
> > +     memset(frame, 0, sizeof(*frame));
> > +
> > +     if (priv->can_idx == 0)
> > +             frame->tag = NCT6694_CAN_FRAME_TAG_CAN0;
> > +     else
> > +             frame->tag = NCT6694_CAN_FRAME_TAG_CAN1;
> > +
> > +     if (can_is_canfd_skb(skb)) {
> > +             cfd = (struct canfd_frame *)priv->tx_skb->data;
> > +
> > +             if (cfd->flags & CANFD_BRS)
> > +                     frame->flag |= NCT6694_CAN_FRAME_FLAG_BRS;
> > +
> > +             if (cfd->can_id & CAN_EFF_FLAG) {
> > +                     txid = cfd->can_id & CAN_EFF_MASK;
> > +                     frame->flag |= NCT6694_CAN_FRAME_FLAG_EFF;
> > +             } else {
> > +                     txid = cfd->can_id & CAN_SFF_MASK;
> > +             }
> > +             frame->flag |= NCT6694_CAN_FRAME_FLAG_FD;
> > +             frame->id = cpu_to_le32(txid);
> > +             frame->length = cfd->len;
> > +
> > +             memcpy(frame->data, cfd->data, cfd->len);
> > +     } else {
> > +             cf = (struct can_frame *)priv->tx_skb->data;
> > +
> > +             if (cf->can_id & CAN_RTR_FLAG)
> > +                     frame->flag |= NCT6694_CAN_FRAME_FLAG_RTR;
> > +
> > +             if (cf->can_id & CAN_EFF_FLAG) {
> > +                     txid = cf->can_id & CAN_EFF_MASK;
> > +                     frame->flag |= NCT6694_CAN_FRAME_FLAG_EFF;
> > +             } else {
> > +                     txid = cf->can_id & CAN_SFF_MASK;
> > +             }
> > +             frame->id = cpu_to_le32(txid);
> > +             frame->length = cf->len;
> > +
> > +             memcpy(frame->data, cf->data, cf->len);
>
> Don't copy the payload if the frame is a remote frame.
>

Fix it in the v5.

> > +             }
>         ^^^^^^^^
>
> Bad indentation. Did you run script/checkpatch.pl before sending?
>

I already ran the script, but I'm not sure why it didn't report this error.
I'll fix it in the next patch.

> > +     err = nct6694_write_msg(priv->nct6694, NCT6694_CAN_MOD,
> > +                             NCT6694_CAN_DELIVER(1),
> > +                             sizeof(*frame),
> > +                             frame);
> > +     if (err) {
> > +             netdev_err(ndev, "%s: Tx FIFO full!\n", __func__);
> > +             can_free_echo_skb(ndev, 0, NULL);
> > +             stats->tx_dropped++;
> > +             stats->tx_errors++;
> > +             netif_wake_queue(ndev);
> > +     }
> > +}
> > +
...
> > +static int nct6694_can_set_mode(struct net_device *ndev, enum can_mode mode)
> > +{
> > +     switch (mode) {
> > +     case CAN_MODE_START:
> > +             nct6694_can_clean(ndev);
> > +             nct6694_can_start(ndev);
> > +             netif_wake_queue(ndev);
> > +             break;
>
> Nitpick: here, directly return 0...
>
> > +     default:
> > +             return -EOPNOTSUPP;
> > +     }
> > +
> > +     return 0;
>
> ... and then remove that line.
>

Fix it in v5.

> > +}
> > +

Best regards,
Ming

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support
  2024-12-30  5:56   ` Vincent Mailhol
@ 2025-01-02  5:40     ` Ming Yu
  2025-01-02  9:03       ` Vincent Mailhol
  0 siblings, 1 reply; 22+ messages in thread
From: Ming Yu @ 2025-01-02  5:40 UTC (permalink / raw)
  To: Vincent Mailhol
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni

Dear Vincent,

Thank you for your comments,

Vincent Mailhol <mailhol.vincent@wanadoo.fr> 於 2024年12月30日 週一 下午1:56寫道:
>
> > +config CAN_NCT6694
> > +     tristate "Nuvoton NCT6694 Socket CANfd support"
> > +     depends on MFD_NCT6694
>
> I think it would be better to do a
>
>         select MFD_NCT6694
>
> here.
>
> Then, make MFD_NCT6694 an hidden configuration in a similar fashion as
> MFD_CORE. Alone, CONFIG_MFD_NCT6694 does nothing, so better to hide it
> from the end user.
>
> The comment also applies to the other patches.
>

I understand, but I noticed that in the Kconfig files of other
modules, the dependency is written in the form:
config CAN_NCT6694
        tristate "Nuvoton NCT6694 Socket CANfd support"
        depends on MFD_NCT6694
(e.g. CAN_JANZ_ICAN3, GPIO_DLN2, ...)
Do you think changing it to select MFD_NCT6694 would be better?

Best regards,
Ming

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support
  2025-01-02  5:40     ` Ming Yu
@ 2025-01-02  9:03       ` Vincent Mailhol
  0 siblings, 0 replies; 22+ messages in thread
From: Vincent Mailhol @ 2025-01-02  9:03 UTC (permalink / raw)
  To: Ming Yu
  Cc: linux-kernel, linux-gpio, linux-i2c, linux-can, netdev,
	linux-watchdog, linux-hwmon, linux-rtc, tmyu0, lee, linus.walleij,
	brgl, andi.shyti, mkl, andrew+netdev, davem, edumazet, kuba,
	pabeni, wim, linux, jdelvare, alexandre.belloni

On 02/01/2025 at 14:40, Ming Yu wrote:
> Dear Vincent,
> 
> Thank you for your comments,
> 
> Vincent Mailhol <mailhol.vincent@wanadoo.fr> 於 2024年12月30日 週一 下午1:56寫道:
>>
>>> +config CAN_NCT6694
>>> +     tristate "Nuvoton NCT6694 Socket CANfd support"
>>> +     depends on MFD_NCT6694
>>
>> I think it would be better to do a
>>
>>         select MFD_NCT6694
>>
>> here.
>>
>> Then, make MFD_NCT6694 an hidden configuration in a similar fashion as
>> MFD_CORE. Alone, CONFIG_MFD_NCT6694 does nothing, so better to hide it
>> from the end user.
>>
>> The comment also applies to the other patches.
>>
> 
> I understand, but I noticed that in the Kconfig files of other
> modules, the dependency is written in the form:
> config CAN_NCT6694
>         tristate "Nuvoton NCT6694 Socket CANfd support"
>         depends on MFD_NCT6694
> (e.g. CAN_JANZ_ICAN3, GPIO_DLN2, ...)
> Do you think changing it to select MFD_NCT6694 would be better?

That's a fair point. Looking at the examples you provided, your approach
makes sense. Please ignore my comment here.


Yours sincerely,
Vincent Mailhol


^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 6/7] hwmon: Add Nuvoton NCT6694 HWMON support
  2024-12-27  9:57 ` [PATCH v4 6/7] hwmon: Add Nuvoton NCT6694 HWMON support Ming Yu
@ 2025-01-06 13:51   ` Simon Horman
  2025-01-13  3:00     ` Ming Yu
  0 siblings, 1 reply; 22+ messages in thread
From: Simon Horman @ 2025-01-06 13:51 UTC (permalink / raw)
  To: Ming Yu
  Cc: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni, linux-kernel, linux-gpio, linux-i2c,
	linux-can, netdev, linux-watchdog, linux-hwmon, linux-rtc

On Fri, Dec 27, 2024 at 05:57:26PM +0800, Ming Yu wrote:
> This driver supports Hardware monitor functionality for NCT6694 MFD
> device based on USB interface.
> 
> Signed-off-by: Ming Yu <a0282524688@gmail.com>

...

> diff --git a/drivers/hwmon/nct6694-hwmon.c b/drivers/hwmon/nct6694-hwmon.c

...

> +struct __packed nct6694_hwmon_alarm {
> +	u8 smi_ctrl;
> +	u8 reserved1[15];
> +	struct {
> +		u8 hl;
> +		u8 ll;
> +	} vin_limit[16];
> +	struct {
> +		u8 hyst;
> +		s8 hl;
> +	} tin_cfg[32];
> +	__be16 fin_ll[10];
> +	u8 reserved2[4];
> +};

...

> +union nct6694_hwmon_rpt {
> +	u8 vin;
> +	struct {
> +		u8 msb;
> +		u8 lsb;
> +	} tin;
> +	__be16 fin;
> +	u8 pwm;
> +	u8 status;
> +};
> +
> +union nct6694_hwmon_msg {
> +	struct nct6694_hwmon_control hwmon_ctrl;
> +	struct nct6694_hwmon_alarm hwmon_alarm;
> +	struct nct6694_pwm_control pwm_ctrl;
> +};
> +
> +struct nct6694_hwmon_data {
> +	struct nct6694 *nct6694;
> +	struct mutex lock;
> +	struct nct6694_hwmon_control hwmon_en;
> +	union nct6694_hwmon_rpt *rpt;
> +	union nct6694_hwmon_msg *msg;
> +};

...

> +static int nct6694_pwm_read(struct device *dev, u32 attr, int channel,
> +			    long *val)
> +{
> +	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
> +	unsigned char pwm_en;
> +	int ret;
> +
> +	guard(mutex)(&data->lock);
> +
> +	switch (attr) {
> +	case hwmon_pwm_enable:
> +		pwm_en = data->hwmon_en.pwm_en[channel / 8];
> +		*val = !!(pwm_en & BIT(channel % 8));
> +
> +		return 0;
> +	case hwmon_pwm_input:
> +		ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
> +				       NCT6694_PWM_IDX(channel),
> +				       sizeof(data->rpt->fin),
> +				       &data->rpt->fin);
> +		if (ret)
> +			return ret;
> +
> +		*val = data->rpt->fin;

Hi Ming Yu,

*val is host byte order, but fin is big endian.
Elsewhere in this patch this seems to be handled using,
which looks correct to me:

		*val = be16_to_cpu(data->rpt->fin);

Flagged by Sparse.

> +
> +		return 0;
> +	case hwmon_pwm_freq:
> +		*val = NCT6694_FREQ_FROM_REG(data->hwmon_en.pwm_freq[channel]);
> +
> +		return 0;
> +	default:
> +		return -EOPNOTSUPP;
> +	}
> +}

...

> +static int nct6694_fan_write(struct device *dev, u32 attr, int channel,
> +			     long val)
> +{
> +	struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
> +	int ret;
> +
> +	guard(mutex)(&data->lock);
> +
> +	switch (attr) {
> +	case hwmon_fan_enable:
> +		if (val == 0)
> +			data->hwmon_en.fin_en[channel / 8] &= ~BIT(channel % 8);
> +		else if (val == 1)
> +			data->hwmon_en.fin_en[channel / 8] |= BIT(channel % 8);
> +		else
> +			return -EINVAL;
> +
> +		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
> +					 NCT6694_HWMON_CONTROL,
> +					 sizeof(data->msg->hwmon_ctrl),
> +					 &data->hwmon_en);
> +	case hwmon_fan_min:
> +		ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
> +				       NCT6694_HWMON_ALARM,
> +				       sizeof(data->msg->hwmon_alarm),
> +				       &data->msg->hwmon_alarm);
> +		if (ret)
> +			return ret;
> +
> +		val = clamp_val(val, 1, 65535);
> +		data->msg->hwmon_alarm.fin_ll[channel] = (u16)cpu_to_be16(val);

cpu_to_be16() returns a 16bit big endian value.
And, AFAIKT, the type of data->msg->hwmon_alarm.fin_ll[channel] is __be16.

So the cast above seems both unnecessary and misleading.

Also flagged by Sparse,

> +
> +		return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
> +					 NCT6694_HWMON_ALARM,
> +					 sizeof(data->msg->hwmon_alarm),
> +					 &data->msg->hwmon_alarm);
> +	default:
> +		return -EOPNOTSUPP;
> +	}
> +}

...

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 6/7] hwmon: Add Nuvoton NCT6694 HWMON support
  2025-01-06 13:51   ` Simon Horman
@ 2025-01-13  3:00     ` Ming Yu
  0 siblings, 0 replies; 22+ messages in thread
From: Ming Yu @ 2025-01-13  3:00 UTC (permalink / raw)
  To: Simon Horman
  Cc: tmyu0, lee, linus.walleij, brgl, andi.shyti, mkl, mailhol.vincent,
	andrew+netdev, davem, edumazet, kuba, pabeni, wim, linux,
	jdelvare, alexandre.belloni, linux-kernel, linux-gpio, linux-i2c,
	linux-can, netdev, linux-watchdog, linux-hwmon, linux-rtc

Dear Simon,

Thank you for your comments,

Simon Horman <horms@kernel.org> 於 2025年1月6日 週一 下午9:51寫道:
>
...
> > +static int nct6694_pwm_read(struct device *dev, u32 attr, int channel,
> > +                         long *val)
> > +{
> > +     struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
> > +     unsigned char pwm_en;
> > +     int ret;
> > +
> > +     guard(mutex)(&data->lock);
> > +
> > +     switch (attr) {
> > +     case hwmon_pwm_enable:
> > +             pwm_en = data->hwmon_en.pwm_en[channel / 8];
> > +             *val = !!(pwm_en & BIT(channel % 8));
> > +
> > +             return 0;
> > +     case hwmon_pwm_input:
> > +             ret = nct6694_read_msg(data->nct6694, NCT6694_RPT_MOD,
> > +                                    NCT6694_PWM_IDX(channel),
> > +                                    sizeof(data->rpt->fin),
> > +                                    &data->rpt->fin);
> > +             if (ret)
> > +                     return ret;
> > +
> > +             *val = data->rpt->fin;
>
> Hi Ming Yu,
>
> *val is host byte order, but fin is big endian.
> Elsewhere in this patch this seems to be handled using,
> which looks correct to me:
>
>                 *val = be16_to_cpu(data->rpt->fin);
>
> Flagged by Sparse.
>

Yes, it needs to be fixed to be16_to_cpu(). I'll make the modification
in the next patch.

> > +
> > +             return 0;
> > +     case hwmon_pwm_freq:
> > +             *val = NCT6694_FREQ_FROM_REG(data->hwmon_en.pwm_freq[channel]);
> > +
> > +             return 0;
> > +     default:
> > +             return -EOPNOTSUPP;
> > +     }
> > +}
>
> ...
>
> > +static int nct6694_fan_write(struct device *dev, u32 attr, int channel,
> > +                          long val)
> > +{
> > +     struct nct6694_hwmon_data *data = dev_get_drvdata(dev);
> > +     int ret;
> > +
> > +     guard(mutex)(&data->lock);
> > +
> > +     switch (attr) {
> > +     case hwmon_fan_enable:
> > +             if (val == 0)
> > +                     data->hwmon_en.fin_en[channel / 8] &= ~BIT(channel % 8);
> > +             else if (val == 1)
> > +                     data->hwmon_en.fin_en[channel / 8] |= BIT(channel % 8);
> > +             else
> > +                     return -EINVAL;
> > +
> > +             return nct6694_write_msg(data->nct6694, NCT6694_HWMON_MOD,
> > +                                      NCT6694_HWMON_CONTROL,
> > +                                      sizeof(data->msg->hwmon_ctrl),
> > +                                      &data->hwmon_en);
> > +     case hwmon_fan_min:
> > +             ret = nct6694_read_msg(data->nct6694, NCT6694_HWMON_MOD,
> > +                                    NCT6694_HWMON_ALARM,
> > +                                    sizeof(data->msg->hwmon_alarm),
> > +                                    &data->msg->hwmon_alarm);
> > +             if (ret)
> > +                     return ret;
> > +
> > +             val = clamp_val(val, 1, 65535);
> > +             data->msg->hwmon_alarm.fin_ll[channel] = (u16)cpu_to_be16(val);
>
> cpu_to_be16() returns a 16bit big endian value.
> And, AFAIKT, the type of data->msg->hwmon_alarm.fin_ll[channel] is __be16.
>
> So the cast above seems both unnecessary and misleading.
>
> Also flagged by Sparse,
>

Understood. Fix it in v5.

> ...

Best regards,
Ming

^ permalink raw reply	[flat|nested] 22+ messages in thread

* Re: [PATCH v4 2/7] gpio: Add Nuvoton NCT6694 GPIO support
  2024-12-27  9:57 ` [PATCH v4 2/7] gpio: Add Nuvoton NCT6694 GPIO support Ming Yu
@ 2025-01-13 14:27   ` Linus Walleij
  0 siblings, 0 replies; 22+ messages in thread
From: Linus Walleij @ 2025-01-13 14:27 UTC (permalink / raw)
  To: Ming Yu
  Cc: tmyu0, lee, brgl, andi.shyti, mkl, mailhol.vincent, andrew+netdev,
	davem, edumazet, kuba, pabeni, wim, linux, jdelvare,
	alexandre.belloni, linux-kernel, linux-gpio, linux-i2c, linux-can,
	netdev, linux-watchdog, linux-hwmon, linux-rtc

On Fri, Dec 27, 2024 at 10:57 AM Ming Yu <a0282524688@gmail.com> wrote:

> This driver supports GPIO and IRQ functionality for NCT6694 MFD
> device based on USB interface.
>
> Signed-off-by: Ming Yu <a0282524688@gmail.com>

This driver looks completely reasonable to me.
Reviewed-by: Linus Walleij <linus.walleij@linaro.org>

Yours,
Linus Walleij

^ permalink raw reply	[flat|nested] 22+ messages in thread

end of thread, other threads:[~2025-01-13 14:27 UTC | newest]

Thread overview: 22+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2024-12-27  9:57 [PATCH v4 0/7] Add Nuvoton NCT6694 MFD drivers Ming Yu
2024-12-27  9:57 ` [PATCH v4 1/7] mfd: Add core driver for Nuvoton NCT6694 Ming Yu
2024-12-27 15:34   ` Vincent Mailhol
2024-12-30  6:32     ` Ming Yu
2024-12-30  7:33       ` Vincent Mailhol
2024-12-30  8:47         ` Ming Yu
2024-12-30  9:38           ` Vincent Mailhol
2024-12-27  9:57 ` [PATCH v4 2/7] gpio: Add Nuvoton NCT6694 GPIO support Ming Yu
2025-01-13 14:27   ` Linus Walleij
2024-12-27  9:57 ` [PATCH v4 3/7] i2c: Add Nuvoton NCT6694 I2C support Ming Yu
2024-12-27  9:57 ` [PATCH v4 4/7] can: Add Nuvoton NCT6694 CAN support Ming Yu
2024-12-27 15:59   ` Vincent Mailhol
2025-01-02  5:25     ` Ming Yu
2024-12-30  5:56   ` Vincent Mailhol
2025-01-02  5:40     ` Ming Yu
2025-01-02  9:03       ` Vincent Mailhol
2024-12-27  9:57 ` [PATCH v4 5/7] watchdog: Add Nuvoton NCT6694 WDT support Ming Yu
2024-12-27  9:57 ` [PATCH v4 6/7] hwmon: Add Nuvoton NCT6694 HWMON support Ming Yu
2025-01-06 13:51   ` Simon Horman
2025-01-13  3:00     ` Ming Yu
2024-12-27  9:57 ` [PATCH v4 7/7] rtc: Add Nuvoton NCT6694 RTC support Ming Yu
2024-12-30 15:39   ` Alexandre Belloni

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).