linux-i2c.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH 0/2] I2C controller support for KEBA PLCs
@ 2024-06-01 19:28 Gerhard Engleder
  2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
  2024-06-01 19:28 ` [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support Gerhard Engleder
  0 siblings, 2 replies; 13+ messages in thread
From: Gerhard Engleder @ 2024-06-01 19:28 UTC (permalink / raw)
  To: linux-i2c; +Cc: andi.shyti, arnd, gregkh, Gerhard Engleder

KEBA PLCs use a PCIe FPGA to implement several functions in a common
way. This is a first step to include basic support for this FPGA.

Under drivers/misc the cp500 PCI driver is added. This drivers creates
platform devices for every function inside the FPGA. As a first step it
only creates platform devices for the I2C controllers.

The I2C controller driver is added under drivers/i2c/busses like all the
other I2C controller drivers.

This patches enable access to the EEPROMs and to the hardware monitoring
chip of KEBA PLCs.

Gerhard Engleder (2):
  i2c: keba: Add KEBA I2C controller support
  misc: keba: Add basic KEBA CP500 system FPGA support

 drivers/i2c/busses/Kconfig             |  10 +
 drivers/i2c/busses/Makefile            |   1 +
 drivers/i2c/busses/i2c-keba.c          | 585 +++++++++++++++++++++++++
 drivers/misc/Kconfig                   |   1 +
 drivers/misc/Makefile                  |   1 +
 drivers/misc/keba/Kconfig              |  12 +
 drivers/misc/keba/Makefile             |   3 +
 drivers/misc/keba/cp500.c              | 433 ++++++++++++++++++
 include/linux/platform_data/i2c-keba.h |  23 +
 9 files changed, 1069 insertions(+)
 create mode 100644 drivers/i2c/busses/i2c-keba.c
 create mode 100644 drivers/misc/keba/Kconfig
 create mode 100644 drivers/misc/keba/Makefile
 create mode 100644 drivers/misc/keba/cp500.c
 create mode 100644 include/linux/platform_data/i2c-keba.h

-- 
2.39.2


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

* [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
  2024-06-01 19:28 [PATCH 0/2] I2C controller support for KEBA PLCs Gerhard Engleder
@ 2024-06-01 19:28 ` Gerhard Engleder
  2024-06-01 22:52   ` kernel test robot
                     ` (4 more replies)
  2024-06-01 19:28 ` [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support Gerhard Engleder
  1 sibling, 5 replies; 13+ messages in thread
From: Gerhard Engleder @ 2024-06-01 19:28 UTC (permalink / raw)
  To: linux-i2c; +Cc: andi.shyti, arnd, gregkh, Gerhard Engleder, Gerhard Engleder

From: Gerhard Engleder <eg@keba.com>

The KEBA I2C controller is found in the system FPGA of KEBA PLC devices.
It is used to connect EEPROMs and hardware monitoring chips.

Signed-off-by: Gerhard Engleder <eg@keba.com>
---
 drivers/i2c/busses/Kconfig             |  10 +
 drivers/i2c/busses/Makefile            |   1 +
 drivers/i2c/busses/i2c-keba.c          | 585 +++++++++++++++++++++++++
 include/linux/platform_data/i2c-keba.h |  23 +
 4 files changed, 619 insertions(+)
 create mode 100644 drivers/i2c/busses/i2c-keba.c
 create mode 100644 include/linux/platform_data/i2c-keba.h

diff --git a/drivers/i2c/busses/Kconfig b/drivers/i2c/busses/Kconfig
index fe6e8a1bb607..be2611a33503 100644
--- a/drivers/i2c/busses/Kconfig
+++ b/drivers/i2c/busses/Kconfig
@@ -770,6 +770,16 @@ config I2C_JZ4780
 
 	 If you don't know what to do here, say N.
 
+config I2C_KEBA
+	tristate "KEBA I2C controller support"
+	depends on HAS_IOMEM
+	help
+	  This driver supports the I2C controller found in KEBA system FPGA
+	  devices.
+
+	  This driver can also be built as a module. If so, the module
+	  will be called i2c-keba.
+
 config I2C_KEMPLD
 	tristate "Kontron COM I2C Controller"
 	depends on MFD_KEMPLD
diff --git a/drivers/i2c/busses/Makefile b/drivers/i2c/busses/Makefile
index 3d65934f5eb4..6c3dfa7936c7 100644
--- a/drivers/i2c/busses/Makefile
+++ b/drivers/i2c/busses/Makefile
@@ -77,6 +77,7 @@ obj-$(CONFIG_I2C_IMX)		+= i2c-imx.o
 obj-$(CONFIG_I2C_IMX_LPI2C)	+= i2c-imx-lpi2c.o
 obj-$(CONFIG_I2C_IOP3XX)	+= i2c-iop3xx.o
 obj-$(CONFIG_I2C_JZ4780)	+= i2c-jz4780.o
+obj-$(CONFIG_I2C_KEBA)		+= i2c-keba.o
 obj-$(CONFIG_I2C_KEMPLD)	+= i2c-kempld.o
 obj-$(CONFIG_I2C_LPC2K)		+= i2c-lpc2k.o
 obj-$(CONFIG_I2C_LS2X)		+= i2c-ls2x.o
diff --git a/drivers/i2c/busses/i2c-keba.c b/drivers/i2c/busses/i2c-keba.c
new file mode 100644
index 000000000000..5f76f0ddeccf
--- /dev/null
+++ b/drivers/i2c/busses/i2c-keba.c
@@ -0,0 +1,585 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Copyright (C) KEBA AG 2012
+ * Copyright (C) KEBA Industrial Automation Gmbh 2024
+ *
+ * Driver for KEBA I2C controller FPGA IP core
+ */
+
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/io.h>
+#include <linux/iopoll.h>
+#include <linux/i2c.h>
+#include <linux/platform_data/i2c-keba.h>
+
+#define KI2C "i2c-keba"
+
+#define KI2C_CAPABILITY_REG	0x02
+#define KI2C_CONTROL_REG	0x04
+#define KI2C_CONTROL_DC_REG	0x05
+#define KI2C_STATUS_REG		0x08
+#define KI2C_STATUS_DC_REG	0x09
+#define KI2C_DATA_REG		0x0c
+
+#define KI2C_CAPABILITY_CRYPTO	0x01
+#define KI2C_CAPABILITY_DC	0x02
+
+#define KI2C_CONTROL_MEN	0x01
+#define KI2C_CONTROL_MSTA	0x02
+#define KI2C_CONTROL_RSTA	0x04
+#define KI2C_CONTROL_MTX	0x08
+#define KI2C_CONTROL_TXAK	0x10
+
+#define KI2C_STATUS_IN_USE	0x01
+#define KI2C_STATUS_ACK_CYC	0x02
+#define KI2C_STATUS_RXAK	0x04
+#define KI2C_STATUS_MCF		0x08
+
+#define KI2C_DC_SDA		0x01
+#define KI2C_DC_SCL		0x02
+
+#define KI2C_INUSE_SLEEP_US	(2 * USEC_PER_MSEC)
+#define KI2C_INUSE_TIMEOUT_US	(10 * USEC_PER_SEC)
+
+#define KI2C_POLL_DELAY_US	5
+
+struct ki2c {
+	struct platform_device *pdev;
+	void __iomem *base;
+	struct i2c_adapter adapter;
+
+	struct i2c_client **client;
+	int client_size;
+};
+
+static int ki2c_inuse_lock(struct ki2c *ki2c)
+{
+	u8 sts;
+	int ret;
+
+	/* The I2C controller has an IN_USE bit for locking access to the
+	 * controller. This enables the use of I2C controller by other none
+	 * Linux processors.
+	 *
+	 * If the I2C controller is free, then the first read returns
+	 * IN_USE == 0. After that the I2C controller is locked and further
+	 * reads of IN_USE return 1.
+	 *
+	 * The I2C controller is unlocked by writing 1 into IN_USE.
+	 */
+	ret = readb_poll_timeout(ki2c->base + KI2C_STATUS_REG,
+				 sts, (sts & KI2C_STATUS_IN_USE) == 0,
+				 KI2C_INUSE_SLEEP_US, KI2C_INUSE_TIMEOUT_US);
+	if (ret != 0)
+		dev_warn(&ki2c->pdev->dev, "%s err!\n", __func__);
+
+	return ret;
+}
+
+static void ki2c_inuse_unlock(struct ki2c *ki2c)
+{
+	/* unlock the controller by writing 1 into IN_USE */
+	iowrite8(KI2C_STATUS_IN_USE, ki2c->base + KI2C_STATUS_REG);
+}
+
+static int ki2c_wait_for_bit(u8 mask, void __iomem *addr, unsigned long timeout)
+{
+	u8 val;
+
+	return readb_poll_timeout(addr, val, (val & mask), KI2C_POLL_DELAY_US,
+				  jiffies_to_usecs(timeout));
+}
+
+static int ki2c_wait_for_mcf(struct ki2c *ki2c)
+{
+	return ki2c_wait_for_bit(KI2C_STATUS_MCF, ki2c->base + KI2C_STATUS_REG,
+				 ki2c->adapter.timeout);
+}
+
+static int ki2c_wait_for_data(struct ki2c *ki2c)
+{
+	int ret;
+
+	ret = ki2c_wait_for_mcf(ki2c);
+	if (ret < 0)
+		return ret;
+
+	return ki2c_wait_for_bit(KI2C_STATUS_ACK_CYC,
+				 ki2c->base + KI2C_STATUS_REG,
+				 ki2c->adapter.timeout);
+}
+
+static int ki2c_wait_for_data_ack(struct ki2c *ki2c)
+{
+	int ret;
+
+	ret = ki2c_wait_for_data(ki2c);
+	if (ret < 0)
+		return ret;
+
+	/* RXAK == 0 means ACK reveived */
+	if (ioread8(ki2c->base + KI2C_STATUS_REG) & KI2C_STATUS_RXAK)
+		return -EIO;
+
+	return 0;
+}
+
+static int ki2c_has_capability(struct ki2c *ki2c, unsigned int cap)
+{
+	return (ioread8(ki2c->base + KI2C_CAPABILITY_REG) & cap) != 0;
+}
+
+static int ki2c_get_scl(struct ki2c *ki2c)
+{
+	/* capability KI2C_CAPABILITY_DC required */
+	return (ioread8(ki2c->base + KI2C_STATUS_DC_REG) & KI2C_DC_SCL) != 0;
+}
+
+static int ki2c_get_sda(struct ki2c *ki2c)
+{
+	/* capability KI2C_CAPABILITY_DC required */
+	return (ioread8(ki2c->base + KI2C_STATUS_DC_REG) & KI2C_DC_SDA) != 0;
+}
+
+static void ki2c_set_scl(struct ki2c *ki2c, int val)
+{
+	u8 control_dc;
+
+	/* capability KI2C_CAPABILITY_DC and KI2C_CONTROL_MEN = 0 reqired */
+	control_dc = ioread8(ki2c->base + KI2C_CONTROL_DC_REG);
+	if (val)
+		control_dc |= KI2C_DC_SCL;
+	else
+		control_dc &= ~KI2C_DC_SCL;
+	iowrite8(control_dc, ki2c->base + KI2C_CONTROL_DC_REG);
+}
+
+/*
+ * Resetting bus bitwise is done by checking SDA and applying clock cycles as
+ * long as SDA is low. 9 clock cycles are applied at most.
+ *
+ * Clock cycles are generated and ndelay() determines the duration of clock
+ * cycles. Generated clock rate is 100 KHz and so duration of both clock levels
+ * is: delay in ns = (10^6 / 100) / 2
+ */
+#define KI2C_RECOVERY_CLK_CNT	9
+#define KI2C_RECOVERY_NDELAY	5000
+static int ki2c_reset_bus_bitwise(struct ki2c *ki2c)
+{
+	int count = 0;
+	int val = 1;
+	int ret = 0;
+
+	/* disable I2C controller (MEN = 0) to get direct access to SCL/SDA */
+	iowrite8(0, ki2c->base + KI2C_CONTROL_REG);
+
+	/* generate clock cycles */
+	ki2c_set_scl(ki2c, val);
+	ndelay(KI2C_RECOVERY_NDELAY);
+	while (count++ < KI2C_RECOVERY_CLK_CNT * 2) {
+		if (val) {
+			/* SCL shouldn't be low here */
+			if (!ki2c_get_scl(ki2c)) {
+				dev_err(&ki2c->pdev->dev,
+					"SCL is stuck low!\n");
+				ret = -EBUSY;
+				break;
+			}
+
+			/* break if SDA is high */
+			if (ki2c_get_sda(ki2c))
+				break;
+		}
+
+		val = !val;
+		ki2c_set_scl(ki2c, val);
+		ndelay(KI2C_RECOVERY_NDELAY);
+	}
+
+	if (!ki2c_get_sda(ki2c)) {
+		dev_err(&ki2c->pdev->dev, "SDA is still low!\n");
+		ret = -EBUSY;
+	}
+
+	/* reenable controller */
+	iowrite8(KI2C_CONTROL_MEN, ki2c->base + KI2C_CONTROL_REG);
+
+	return ret;
+}
+
+/*
+ * Resetting bus bytewise is done by writing start bit, 9 data bits and stop
+ * bit.
+ *
+ * This is not 100% safe. If slave is an EEPROM and a write access was
+ * interrupted during the ACK cycle, this approach might not be able to recover
+ * the bus. The reason is, that after the 9 clock cycles the EEPROM will be in
+ * ACK cycle again and will hold SDA low like it did before the start of the
+ * routine. Furthermore the EEPROM might get written one additional byte with
+ * 0xff into it. Thus, use bitwise approach whenever possible, especially when
+ * EEPROMs are on the bus.
+ */
+static int ki2c_reset_bus_bytewise(struct ki2c *ki2c)
+{
+	int ret;
+
+	/* hold data line high for 9 clock cycles */
+	iowrite8(0xFF, ki2c->base + KI2C_DATA_REG);
+
+	/* create start condition */
+	iowrite8(KI2C_CONTROL_MEN | KI2C_CONTROL_MTX | KI2C_CONTROL_MSTA | KI2C_CONTROL_TXAK,
+		 ki2c->base + KI2C_CONTROL_REG);
+	ret = ki2c_wait_for_mcf(ki2c);
+	if (ret < 0)
+		return ret;
+
+	/* create stop condition */
+	iowrite8(KI2C_CONTROL_MEN | KI2C_CONTROL_MTX | KI2C_CONTROL_TXAK,
+		 ki2c->base + KI2C_CONTROL_REG);
+	ret = ki2c_wait_for_mcf(ki2c);
+
+	return ret;
+}
+
+static int ki2c_reset_bus(struct ki2c *ki2c)
+{
+	int ret;
+
+	ret = ki2c_inuse_lock(ki2c);
+	if (ret < 0)
+		return ret;
+
+	/* If the I2C controller is capable of direct control of SCL/SDA, then a
+	 * bitwise reset is used. Otherwise fall back to bytewise reset.
+	 */
+	if (ki2c_has_capability(ki2c, KI2C_CAPABILITY_DC))
+		ret = ki2c_reset_bus_bitwise(ki2c);
+	else
+		ret = ki2c_reset_bus_bytewise(ki2c);
+
+	ki2c_inuse_unlock(ki2c);
+
+	return ret;
+}
+
+static void ki2c_write_target_addr(struct ki2c *ki2c, struct i2c_msg *m)
+{
+	u8 addr;
+
+	addr = m->addr << 1;
+	/* Bit 0 signals RD/WR */
+	if (m->flags & I2C_M_RD)
+		addr |= 0x01;
+
+	iowrite8(addr, ki2c->base + KI2C_DATA_REG);
+}
+
+static int ki2c_start_addr(struct ki2c *ki2c, struct i2c_msg *m)
+{
+	int ret;
+
+	/* Store target address byte in the controller. This has to be done
+	 * before sending START condition.
+	 */
+	ki2c_write_target_addr(ki2c, m);
+
+	/* enable controller for TX */
+	iowrite8(KI2C_CONTROL_MEN | KI2C_CONTROL_MTX,
+		 ki2c->base + KI2C_CONTROL_REG);
+
+	/* send START condition and target address byte */
+	iowrite8(KI2C_CONTROL_MEN | KI2C_CONTROL_MTX | KI2C_CONTROL_MSTA,
+		 ki2c->base + KI2C_CONTROL_REG);
+
+	ret = ki2c_wait_for_data_ack(ki2c);
+	if (ret < 0)
+		/* For EEPROMs this is normal behavior during internal write
+		 * operation.
+		 */
+		dev_dbg(&ki2c->pdev->dev, "%s wait for ACK err at 0x%02x!\n",
+			__func__, m->addr);
+
+	return ret;
+}
+
+static int ki2c_repstart_addr(struct ki2c *ki2c, struct i2c_msg *m)
+{
+	int ret;
+
+	/* repeated start and write is not supported */
+	if ((m->flags & I2C_M_RD) == 0) {
+		dev_warn(&ki2c->pdev->dev,
+			 "Repeated start not supported for writes\n");
+		return -EINVAL;
+	}
+
+	/* send repeated start */
+	iowrite8(KI2C_CONTROL_MEN | KI2C_CONTROL_MSTA | KI2C_CONTROL_RSTA,
+		 ki2c->base + KI2C_CONTROL_REG);
+
+	ret = ki2c_wait_for_mcf(ki2c);
+	if (ret < 0) {
+		dev_warn(&ki2c->pdev->dev, "%s wait for MCF err at 0x%02x!\n",
+			 __func__, m->addr);
+		return ret;
+	}
+
+	/* write target-address byte */
+	ki2c_write_target_addr(ki2c, m);
+
+	ret = ki2c_wait_for_data_ack(ki2c);
+	if (ret < 0)
+		dev_warn(&ki2c->pdev->dev, "%s wait for ACK err at 0x%02x!\n",
+			 __func__, m->addr);
+
+	return ret;
+}
+
+static void ki2c_stop(struct ki2c *ki2c)
+{
+	iowrite8(KI2C_CONTROL_MEN, ki2c->base + KI2C_CONTROL_REG);
+	ki2c_wait_for_mcf(ki2c);
+}
+
+static int ki2c_write(struct ki2c *ki2c, const u8 *data, int len)
+{
+	int ret;
+
+	for (int i = 0; i < len; i++) {
+		/* write data byte */
+		iowrite8(data[i], ki2c->base + KI2C_DATA_REG);
+
+		ret = ki2c_wait_for_data_ack(ki2c);
+		if (ret < 0)
+			return ret;
+	}
+
+	return 0;
+}
+
+static int ki2c_read(struct ki2c *ki2c, u8 *data, int len)
+{
+	u8 control;
+	int ret;
+
+	if (len == 0)
+		return 0;	/* nothing to do */
+
+	control = KI2C_CONTROL_MEN | KI2C_CONTROL_MSTA;
+
+	/* if just one byte => send tx-nack after transfer */
+	if (len == 1)
+		control |= KI2C_CONTROL_TXAK;
+
+	iowrite8(control, ki2c->base + KI2C_CONTROL_REG);
+
+	/* dummy read to start transfer on bus */
+	ioread8(ki2c->base + KI2C_DATA_REG);
+
+	for (int i = 0; i < len; i++) {
+		ret = ki2c_wait_for_data(ki2c);
+		if (ret < 0)
+			return ret;
+
+		/* send tx-nack after transfer of last byte */
+		if (i == len - 2)
+			iowrite8(KI2C_CONTROL_MEN | KI2C_CONTROL_MSTA | KI2C_CONTROL_TXAK,
+				 ki2c->base + KI2C_CONTROL_REG);
+
+		/* switch to TX on last byte, so that reading DATA-register
+		 * does not trigger another read transfer.
+		 */
+		if (i == len - 1)
+			iowrite8(KI2C_CONTROL_MEN | KI2C_CONTROL_MSTA | KI2C_CONTROL_MTX,
+				 ki2c->base + KI2C_CONTROL_REG);
+
+		/* read byte and start next transfer (if not last byte) */
+		data[i] = ioread8(ki2c->base + KI2C_DATA_REG);
+	}
+
+	return len;
+}
+
+static int ki2c_xfer(struct i2c_adapter *adap, struct i2c_msg msgs[], int num)
+{
+	struct ki2c *ki2c = i2c_get_adapdata(adap);
+	int ret;
+
+	ret = ki2c_inuse_lock(ki2c);
+	if (ret < 0)
+		return ret;
+
+	for (int i = 0; i < num; i++) {
+		struct i2c_msg *m = &msgs[i];
+
+		if (i == 0)
+			ret = ki2c_start_addr(ki2c, m);
+		else
+			ret = ki2c_repstart_addr(ki2c, m);
+		if (ret < 0)
+			break;
+
+		if (m->flags & I2C_M_RD)
+			ret = ki2c_read(ki2c, m->buf, m->len);
+		else
+			ret = ki2c_write(ki2c, m->buf, m->len);
+		if (ret < 0)
+			break;
+	}
+
+	ki2c_stop(ki2c);
+
+	ki2c_inuse_unlock(ki2c);
+
+	return (ret < 0) ? ret : num;
+}
+
+static void ki2c_unregister_devices(struct ki2c *ki2c)
+{
+	for (int i = 0; i < ki2c->client_size; i++) {
+		struct i2c_client *client = ki2c->client[i];
+
+		if (client)
+			i2c_unregister_device(client);
+	}
+}
+
+static int ki2c_register_devices(struct ki2c *ki2c,
+				 struct i2c_keba_platform_data *pdata)
+{
+	/* register all I2C devices from platform_data array */
+	for (int i = 0; i < ki2c->client_size; i++) {
+		struct i2c_client *client;
+		unsigned short const addr_list[2] = { pdata->info[i].addr,
+						      I2C_CLIENT_END };
+
+		client = i2c_new_scanned_device(&ki2c->adapter, &pdata->info[i],
+						addr_list, NULL);
+		if (!IS_ERR(client)) {
+			ki2c->client[i] = client;
+		} else if (PTR_ERR(client) != -ENODEV) {
+			ki2c_unregister_devices(ki2c);
+
+			return PTR_ERR(client);
+		}
+	}
+
+	return 0;
+}
+
+static u32 ki2c_func(struct i2c_adapter *adap)
+{
+	return I2C_FUNC_I2C | I2C_FUNC_SMBUS_EMUL;
+}
+
+static const struct i2c_algorithm ki2c_algo = {
+	.master_xfer   = ki2c_xfer,
+	.functionality = ki2c_func,
+};
+
+static int ki2c_probe(struct platform_device *pdev)
+{
+	struct i2c_keba_platform_data *pdata;
+	struct device *dev = &pdev->dev;
+	struct i2c_adapter *adap;
+	struct resource *io;
+	struct ki2c *ki2c;
+	int ret;
+
+	pdata = dev->platform_data;
+	if (pdata == 0) {
+		dev_err(dev, "Platform data not found!\n");
+		return -ENODEV;
+	}
+
+	ki2c = devm_kzalloc(dev, sizeof(*ki2c), GFP_KERNEL);
+	if (!ki2c)
+		return -ENOMEM;
+	ki2c->pdev = pdev;
+	ki2c->client = devm_kcalloc(dev, pdata->info_size,
+				    sizeof(*ki2c->client), GFP_KERNEL);
+	if (!ki2c->client)
+		return -ENOMEM;
+	ki2c->client_size = pdata->info_size;
+	platform_set_drvdata(pdev, ki2c);
+
+	io = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+	ki2c->base = devm_ioremap_resource(dev, io);
+	if (IS_ERR(ki2c->base))
+		return PTR_ERR(ki2c->base);
+
+	/* enable controller */
+	iowrite8(KI2C_CONTROL_MEN, ki2c->base + KI2C_CONTROL_REG);
+
+	adap = &ki2c->adapter;
+	strscpy(adap->name, "KEBA I2C adapter", sizeof(adap->name));
+	adap->owner = THIS_MODULE;
+	adap->class = I2C_CLASS_HWMON;
+	adap->algo = &ki2c_algo;
+	adap->dev.parent = dev;
+
+	i2c_set_adapdata(adap, ki2c);
+
+	/* reset bus before probing I2C devices */
+	ret = ki2c_reset_bus(ki2c);
+	if (ret) {
+		dev_err(dev, "Failed to reset bus (%d)!\n", ret);
+		goto out_disable;
+	}
+
+	ret = i2c_add_adapter(adap);
+	if (ret) {
+		dev_err(dev, "Failed to add adapter (%d)!\n", ret);
+		goto out_disable;
+	}
+
+	ret = ki2c_register_devices(ki2c, pdata);
+	if (ret) {
+		dev_err(dev, "Failed to register devices (%d)!\n", ret);
+		goto out_delete;
+	}
+
+	return 0;
+
+out_delete:
+	i2c_del_adapter(adap);
+out_disable:
+	iowrite8(0, ki2c->base + KI2C_CONTROL_REG);
+	return ret;
+}
+
+static int ki2c_remove(struct platform_device *pdev)
+{
+	struct ki2c *ki2c = platform_get_drvdata(pdev);
+
+	ki2c_unregister_devices(ki2c);
+
+	i2c_del_adapter(&ki2c->adapter);
+
+	/* disable controller */
+	iowrite8(0, ki2c->base + KI2C_CONTROL_REG);
+
+	platform_set_drvdata(pdev, 0);
+
+	return 0;
+}
+
+static struct platform_device_id ki2c_devtype[] = {
+	{ .name = KI2C },
+	{ }
+};
+MODULE_DEVICE_TABLE(platform, ki2c_devtype);
+
+static struct platform_driver ki2c_driver = {
+	.driver = {
+		.name = KI2C,
+	},
+	.probe = ki2c_probe,
+	.remove = ki2c_remove,
+};
+module_platform_driver(ki2c_driver);
+
+MODULE_AUTHOR("Gerhard Engleder <eg@keba.com>");
+MODULE_DESCRIPTION("KEBA I2C bus controller driver");
+MODULE_LICENSE("GPL");
diff --git a/include/linux/platform_data/i2c-keba.h b/include/linux/platform_data/i2c-keba.h
new file mode 100644
index 000000000000..99d54bcb6ed9
--- /dev/null
+++ b/include/linux/platform_data/i2c-keba.h
@@ -0,0 +1,23 @@
+/* SPDX-License-Identifier: GPL-2.0 */
+/*
+ * Copyright (C) KEBA AG 2012
+ * Copyright (C) KEBA Industrial Automation Gmbh 2024
+ *
+ * Platform data for KEBA I2C controller FPGA IP core
+ */
+
+#ifndef __LINUX_PLATFORM_DATA_I2C_KEBA_H
+#define __LINUX_PLATFORM_DATA_I2C_KEBA_H
+
+/**
+ * Platform data for KEBA I2C controller
+ *
+ * @info I2C devices to be probed
+ * @info_size size of info array
+ */
+struct i2c_keba_platform_data {
+	struct i2c_board_info *info;
+	int info_size;
+};
+
+#endif /* __LINUX_PLATFORM_DATA_I2C_KEBA_H */
-- 
2.39.2


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

* [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support
  2024-06-01 19:28 [PATCH 0/2] I2C controller support for KEBA PLCs Gerhard Engleder
  2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
@ 2024-06-01 19:28 ` Gerhard Engleder
  2024-06-02  7:19   ` Greg KH
                     ` (2 more replies)
  1 sibling, 3 replies; 13+ messages in thread
From: Gerhard Engleder @ 2024-06-01 19:28 UTC (permalink / raw)
  To: linux-i2c; +Cc: andi.shyti, arnd, gregkh, Gerhard Engleder, Gerhard Engleder

From: Gerhard Engleder <eg@keba.com>

The KEBA CP500 system FPGA is a PCIe device, which consists of multiple
IP cores. Every IP core has its own platform driver. The cp500 driver
registers a platform device for each device and the corresponding
drivers are loaded by the Linux driver infrastructure.

Currently 3 variants of this device exists. Every variant has its own
PCI device ID, which is used to determine the list of available IP
cores. In this first version only the platform device for the I2C
controller is registered.

Besides the platform device registration some other basic functions of
the FPGA are implemented; e.g, FPGA version sysfs file, keep FPGA
configuration on reset sysfs file, error message for errors on the
internal AXI bus of the FPGA.

Signed-off-by: Gerhard Engleder <eg@keba.com>
---
 drivers/misc/Kconfig       |   1 +
 drivers/misc/Makefile      |   1 +
 drivers/misc/keba/Kconfig  |  12 +
 drivers/misc/keba/Makefile |   3 +
 drivers/misc/keba/cp500.c  | 433 +++++++++++++++++++++++++++++++++++++
 5 files changed, 450 insertions(+)
 create mode 100644 drivers/misc/keba/Kconfig
 create mode 100644 drivers/misc/keba/Makefile
 create mode 100644 drivers/misc/keba/cp500.c

diff --git a/drivers/misc/Kconfig b/drivers/misc/Kconfig
index faf983680040..ca0c6a728a00 100644
--- a/drivers/misc/Kconfig
+++ b/drivers/misc/Kconfig
@@ -602,4 +602,5 @@ source "drivers/misc/cardreader/Kconfig"
 source "drivers/misc/uacce/Kconfig"
 source "drivers/misc/pvpanic/Kconfig"
 source "drivers/misc/mchp_pci1xxxx/Kconfig"
+source "drivers/misc/keba/Kconfig"
 endmenu
diff --git a/drivers/misc/Makefile b/drivers/misc/Makefile
index 153a3f4837e8..af125aa25a50 100644
--- a/drivers/misc/Makefile
+++ b/drivers/misc/Makefile
@@ -69,3 +69,4 @@ obj-$(CONFIG_TMR_INJECT)	+= xilinx_tmr_inject.o
 obj-$(CONFIG_TPS6594_ESM)	+= tps6594-esm.o
 obj-$(CONFIG_TPS6594_PFSM)	+= tps6594-pfsm.o
 obj-$(CONFIG_NSM)		+= nsm.o
+obj-y				+= keba/
diff --git a/drivers/misc/keba/Kconfig b/drivers/misc/keba/Kconfig
new file mode 100644
index 000000000000..0ebca1d07ef4
--- /dev/null
+++ b/drivers/misc/keba/Kconfig
@@ -0,0 +1,12 @@
+# SPDX-License-Identifier: GPL-2.0
+config KEBA_CP500
+	tristate "KEBA CP500 system FPGA support"
+	depends on PCI
+	help
+	  This driver supports the KEBA CP500 system FPGA, which is used in
+	  KEBA CP500 devices. It registers all sub devices present on the CP500
+	  system FPGA as separate devices. A driver is needed for each sub
+	  device.
+
+	  This driver can also be built as a module. If so, the module will be
+	  called cp500.
diff --git a/drivers/misc/keba/Makefile b/drivers/misc/keba/Makefile
new file mode 100644
index 000000000000..0a8b846cda7d
--- /dev/null
+++ b/drivers/misc/keba/Makefile
@@ -0,0 +1,3 @@
+# SPDX-License-Identifier: GPL-2.0
+
+obj-$(CONFIG_KEBA_CP500)	+= cp500.o
diff --git a/drivers/misc/keba/cp500.c b/drivers/misc/keba/cp500.c
new file mode 100644
index 000000000000..f80f10488b3e
--- /dev/null
+++ b/drivers/misc/keba/cp500.c
@@ -0,0 +1,433 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * Copyright (C) KEBA AG 2012
+ * Copyright (C) KEBA Industrial Automation Gmbh 2024
+ *
+ * Driver for KEBA system FPGA
+ *
+ * The KEBA system FPGA implements various devices. This driver registers
+ * platform devices for every device within the FPGA.
+ */
+
+#include <linux/device.h>
+#include <linux/module.h>
+#include <linux/pci.h>
+#include <linux/platform_device.h>
+#include <linux/i2c.h>
+#include <linux/platform_data/i2c-keba.h>
+
+#define CP500 "cp500"
+
+#define PCI_VENDOR_ID_KEBA		0xCEBA
+#define PCI_DEVICE_ID_KEBA_CP035	0x2706
+#define PCI_DEVICE_ID_KEBA_CP505	0x2703
+#define PCI_DEVICE_ID_KEBA_CP520	0x2696
+
+#define CP500_SYS_BAR		0
+#define CP500_ECM_BAR		1
+
+/* BAR 0 registers */
+#define CP500_VERSION_REG	0x00
+#define CP500_RECONFIG_REG	0x11	/* upper 8-bits of STARTUP register */
+#define CP500_AXI_REG		0x40
+
+/* Bits in BUILD_REG */
+#define CP500_BUILD_TEST        0x8000	/* FPGA test version */
+
+/* Bits in RECONFIG_REG */
+#define CP500_RECFG_REQ		0x01	/* reconfigure FPGA on next reset */
+
+/* MSIX */
+#define CP500_AXI_MSIX		3
+#define CP500_NUM_MSIX		8
+#define CP500_NUM_MSIX_NO_MMI	2
+#define CP500_NUM_MSIX_NO_AXI	3
+
+/* EEPROM */
+#define CP500_HW_CPU_EEPROM_NAME	"cp500_cpu_eeprom"
+
+#define CP500_IS_CP035(dev)	((dev)->pci_dev->device == PCI_DEVICE_ID_KEBA_CP035)
+#define CP500_IS_CP505(dev)	((dev)->pci_dev->device == PCI_DEVICE_ID_KEBA_CP505)
+#define CP500_IS_CP520(dev)	((dev)->pci_dev->device == PCI_DEVICE_ID_KEBA_CP520)
+
+struct cp500_dev_info {
+	off_t offset;
+	size_t size;
+};
+
+struct cp500_devs {
+	struct cp500_dev_info startup;
+	struct cp500_dev_info i2c;
+};
+
+/* list of devices within FPGA of CP035 family (CP035, CP056, CP057) */
+struct cp500_devs cp035_devices = {
+	.startup   = { 0x0000, SZ_4K },
+	.i2c       = { 0x4000, SZ_4K },
+};
+
+/* list of devices within FPGA of CP505 family (CP503, CP505, CP507) */
+struct cp500_devs cp505_devices = {
+	.startup   = { 0x0000, SZ_4K },
+	.i2c       = { 0x5000, SZ_4K },
+};
+
+/* list of devices within FPGA of CP520 family (CP520, CP530) */
+struct cp500_devs cp520_devices = {
+	.startup     = { 0x0000, SZ_4K },
+	.i2c         = { 0x5000, SZ_4K },
+};
+
+struct cp500 {
+	struct pci_dev *pci_dev;
+	struct cp500_devs *devs;
+	int msix_num;
+	struct {
+		int major;
+		int minor;
+		int build;
+	} version;
+
+	/* system FPGA BAR */
+	resource_size_t sys_hwbase;
+	struct platform_device *i2c;
+
+	/* ECM EtherCAT BAR */
+	resource_size_t ecm_hwbase;
+
+	void __iomem *system_startup_addr;
+};
+
+/* I2C devices */
+static struct i2c_board_info cp500_i2c_info[] = {
+	{	/* temperature sensor */
+		I2C_BOARD_INFO("emc1403", 0x4c),
+	},
+	{	/* CPU EEPROM
+		 * CP035 family: CPU board
+		 * CP505 family: bridge board
+		 * CP520 family: carrier board
+		 */
+		I2C_BOARD_INFO("24c32", 0x50),
+		.dev_name = CP500_HW_CPU_EEPROM_NAME,
+	},
+	{	/* interface board EEPROM */
+		I2C_BOARD_INFO("24c32", 0x51),
+	},
+	{	/* EEPROM (optional)
+		 * CP505 family: CPU board
+		 * CP520 family: MMI board
+		 */
+		I2C_BOARD_INFO("24c32", 0x52),
+	},
+	{	/* extension module 0 EEPROM (optional) */
+		I2C_BOARD_INFO("24c32", 0x53),
+	},
+	{	/* extension module 1 EEPROM (optional) */
+		I2C_BOARD_INFO("24c32", 0x54),
+	},
+	{	/* extension module 2 EEPROM (optional) */
+		I2C_BOARD_INFO("24c32", 0x55),
+	},
+	{	/* extension module 3 EEPROM (optional) */
+		I2C_BOARD_INFO("24c32", 0x56),
+	}
+};
+
+static ssize_t cp500_get_fpga_version(struct cp500 *cp500, char *buf,
+				      size_t max_len)
+{
+	int n;
+
+	if (CP500_IS_CP035(cp500))
+		n = scnprintf(buf, max_len, "CP035");
+	else if (CP500_IS_CP505(cp500))
+		n = scnprintf(buf, max_len, "CP505");
+	else
+		n = scnprintf(buf, max_len, "CP500");
+
+	n += scnprintf(buf + n, max_len - n, "_FPGA_%d.%02d",
+		       cp500->version.major, cp500->version.minor);
+
+	/* test versions have test bit set */
+	if (cp500->version.build & CP500_BUILD_TEST)
+		n += scnprintf(buf + n, max_len - n, "Test%d",
+			       cp500->version.build & ~CP500_BUILD_TEST);
+
+	n += scnprintf(buf + n, max_len - n, "\n");
+
+	return n;
+}
+
+static ssize_t version_show(struct device *dev, struct device_attribute *attr,
+			    char *buf)
+{
+	struct cp500 *cp500 = dev_get_drvdata(dev);
+
+	return cp500_get_fpga_version(cp500, buf, PAGE_SIZE);
+}
+static DEVICE_ATTR_RO(version);
+
+static ssize_t keep_cfg_show(struct device *dev, struct device_attribute *attr,
+			     char *buf)
+{
+	struct cp500 *cp500 = dev_get_drvdata(dev);
+	unsigned long keep_cfg = 1;
+
+	/* FPGA configuration stream is kept during reset when RECONFIG bit is
+	 * zero
+	 */
+	if (ioread8(cp500->system_startup_addr + CP500_RECONFIG_REG) &
+		CP500_RECFG_REQ)
+		keep_cfg = 0;
+
+	return sprintf(buf, "%lu\n", keep_cfg);
+}
+
+static ssize_t keep_cfg_store(struct device *dev, struct device_attribute *attr,
+			      const char *buf, size_t count)
+{
+	struct cp500 *cp500 = dev_get_drvdata(dev);
+	unsigned long keep_cfg;
+
+	if (kstrtoul(buf, 10, &keep_cfg) < 0)
+		return -EINVAL;
+
+	/* In normal operation "keep_cfg" is "1". This means that the FPGA keeps
+	 * its configuration stream during a reset.
+	 * In case of a firmware update of the FPGA, the configuration stream
+	 * needs to be reloaded. This can be done without a powercycle by
+	 * writing a "0" into the "keep_cfg" attribute. After a reset/reboot th
+	 * new configuration stream will be loaded.
+	 */
+	if (keep_cfg)
+		iowrite8(0, cp500->system_startup_addr + CP500_RECONFIG_REG);
+	else
+		iowrite8(CP500_RECFG_REQ,
+			 cp500->system_startup_addr + CP500_RECONFIG_REG);
+
+	return count;
+}
+static DEVICE_ATTR_RW(keep_cfg);
+
+static struct attribute *attrs[] = {
+	&dev_attr_version.attr,
+	&dev_attr_keep_cfg.attr,
+	NULL
+};
+static const struct attribute_group attrs_group = { .attrs = attrs };
+
+static int cp500_register_i2c(struct cp500 *cp500)
+{
+	struct i2c_keba_platform_data data;
+	struct platform_device *pdev;
+	struct resource res[] = {
+		{
+		 /* I2C register area */
+		 .start = (resource_size_t) cp500->sys_hwbase +
+			  cp500->devs->i2c.offset,
+		 .end   = (resource_size_t) cp500->sys_hwbase +
+			  cp500->devs->i2c.offset +
+			  cp500->devs->i2c.size - 1,
+		 .flags = IORESOURCE_MEM,
+		 },
+	};
+
+	data.info = cp500_i2c_info;
+	data.info_size = ARRAY_SIZE(cp500_i2c_info);
+
+	pdev = platform_device_register_resndata(&cp500->pci_dev->dev,
+						 "i2c-keba", 0, res,
+						 ARRAY_SIZE(res), &data,
+						 sizeof(data));
+	if (IS_ERR(pdev))
+		return PTR_ERR(pdev);
+	cp500->i2c = pdev;
+
+	return 0;
+}
+
+static void cp500_register_platform_devs(struct cp500 *cp500)
+{
+	struct device *dev = &cp500->pci_dev->dev;
+
+	if (cp500_register_i2c(cp500))
+		dev_warn(dev, "Failed to register i2c-keba!\n");
+}
+
+static void cp500_unregister_dev(struct platform_device **ppdev)
+{
+	if (*ppdev) {
+		platform_device_unregister(*ppdev);
+		*ppdev = 0;
+	}
+}
+
+static void cp500_unregister_platform_devs(struct cp500 *cp500)
+{
+	cp500_unregister_dev(&cp500->i2c);
+}
+
+static irqreturn_t cp500_axi_handler(int irq, void *dev)
+{
+	struct cp500 *cp500 = dev;
+	u32 axi_address = ioread32(cp500->system_startup_addr + CP500_AXI_REG);
+
+	/* FPGA signals AXI response error, print AXI address to indicate which
+	 * IP core was affected
+	 */
+	dev_err(&cp500->pci_dev->dev, "AXI response error at 0x%08x\n",
+		axi_address);
+
+	return IRQ_HANDLED;
+}
+
+static int cp500_enable(struct cp500 *cp500)
+{
+	int axi_irq = -1;
+	int ret;
+
+	if (cp500->msix_num > CP500_NUM_MSIX_NO_AXI) {
+		axi_irq = pci_irq_vector(cp500->pci_dev, CP500_AXI_MSIX);
+		ret = request_irq(axi_irq, cp500_axi_handler, 0,
+				  CP500, cp500);
+		if (ret != 0) {
+			dev_err(&cp500->pci_dev->dev,
+				"Failed to register AXI response error!\n");
+			return ret;
+		}
+	}
+
+	return 0;
+}
+
+static void cp500_disable(struct cp500 *cp500)
+{
+	int axi_irq;
+
+	if (cp500->msix_num > CP500_NUM_MSIX_NO_AXI) {
+		axi_irq = pci_irq_vector(cp500->pci_dev, CP500_AXI_MSIX);
+		free_irq(axi_irq, cp500);
+	}
+}
+
+static int cp500_probe(struct pci_dev *pci_dev, const struct pci_device_id *id)
+{
+	struct device *dev = &pci_dev->dev;
+	struct resource startup;
+	struct cp500 *cp500;
+	u32 cp500_vers;
+	char buf[64];
+	int ret;
+
+	cp500 = devm_kzalloc(dev, sizeof(*cp500), GFP_KERNEL);
+	if (cp500 == 0)
+		return -ENOMEM;
+	cp500->pci_dev = pci_dev;
+	cp500->sys_hwbase = pci_resource_start(pci_dev, CP500_SYS_BAR);
+	cp500->ecm_hwbase = pci_resource_start(pci_dev, CP500_ECM_BAR);
+	if (!cp500->sys_hwbase || !cp500->ecm_hwbase)
+		return -ENODEV;
+
+	if (CP500_IS_CP035(cp500))
+		cp500->devs = &cp035_devices;
+	else if (CP500_IS_CP505(cp500))
+		cp500->devs = &cp505_devices;
+	else if (CP500_IS_CP520(cp500))
+		cp500->devs = &cp520_devices;
+	else
+		return -ENODEV;
+
+	ret = pci_enable_device(pci_dev);
+	if (ret)
+		return ret;
+	pci_set_master(pci_dev);
+
+	startup = *pci_resource_n(pci_dev, CP500_SYS_BAR);
+	startup.end = startup.start + cp500->devs->startup.size - 1;
+	cp500->system_startup_addr = devm_ioremap_resource(&pci_dev->dev,
+							   &startup);
+	if (IS_ERR(cp500->system_startup_addr)) {
+		ret = PTR_ERR(cp500->system_startup_addr);
+		goto out_disable;
+	}
+
+	cp500->msix_num = pci_alloc_irq_vectors(pci_dev, CP500_NUM_MSIX_NO_MMI,
+						CP500_NUM_MSIX, PCI_IRQ_MSIX);
+	if (cp500->msix_num < CP500_NUM_MSIX_NO_MMI) {
+		dev_err(&pci_dev->dev,
+			"Hardware does not support enough MSI-X interrupts\n");
+		ret = -ENODEV;
+		goto out_disable;
+	}
+
+	cp500_vers = ioread32(cp500->system_startup_addr + CP500_VERSION_REG);
+	cp500->version.major = (cp500_vers & 0xff);
+	cp500->version.minor = (cp500_vers >> 8) & 0xff;
+	cp500->version.build = (cp500_vers >> 16) & 0xffff;
+	cp500_get_fpga_version(cp500, buf, sizeof(buf));
+
+	dev_info(&pci_dev->dev, "FPGA version %s", buf);
+
+	pci_set_drvdata(pci_dev, cp500);
+
+	ret = sysfs_create_group(&pci_dev->dev.kobj, &attrs_group);
+	if (ret != 0)
+		goto out_free_irq;
+
+	ret = cp500_enable(cp500);
+	if (ret != 0)
+		goto out_remove_group;
+
+	cp500_register_platform_devs(cp500);
+
+	return 0;
+
+out_remove_group:
+	sysfs_remove_group(&pci_dev->dev.kobj, &attrs_group);
+out_free_irq:
+	pci_free_irq_vectors(pci_dev);
+out_disable:
+	pci_clear_master(pci_dev);
+	pci_disable_device(pci_dev);
+
+	return ret;
+}
+
+static void cp500_remove(struct pci_dev *pci_dev)
+{
+	struct cp500 *cp500 = pci_get_drvdata(pci_dev);
+
+	cp500_unregister_platform_devs(cp500);
+
+	cp500_disable(cp500);
+
+	sysfs_remove_group(&pci_dev->dev.kobj, &attrs_group);
+
+	pci_set_drvdata(pci_dev, 0);
+
+	pci_free_irq_vectors(pci_dev);
+
+	pci_clear_master(pci_dev);
+	pci_disable_device(pci_dev);
+}
+
+static struct pci_device_id cp500_ids[] = {
+	{ PCI_DEVICE(PCI_VENDOR_ID_KEBA, PCI_DEVICE_ID_KEBA_CP035) },
+	{ PCI_DEVICE(PCI_VENDOR_ID_KEBA, PCI_DEVICE_ID_KEBA_CP505) },
+	{ PCI_DEVICE(PCI_VENDOR_ID_KEBA, PCI_DEVICE_ID_KEBA_CP520) },
+	{ }
+};
+MODULE_DEVICE_TABLE(pci, cp500_ids);
+
+static struct pci_driver cp500_driver = {
+	.name = CP500,
+	.id_table = cp500_ids,
+	.probe = cp500_probe,
+	.remove = cp500_remove,
+};
+module_pci_driver(cp500_driver);
+
+MODULE_AUTHOR("Gerhard Engleder <eg@keba.com>");
+MODULE_DESCRIPTION("KEBA CP500 system FPGA driver");
+MODULE_LICENSE("GPL");
-- 
2.39.2


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

* Re: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
  2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
@ 2024-06-01 22:52   ` kernel test robot
  2024-06-01 23:45   ` kernel test robot
                     ` (3 subsequent siblings)
  4 siblings, 0 replies; 13+ messages in thread
From: kernel test robot @ 2024-06-01 22:52 UTC (permalink / raw)
  To: Gerhard Engleder, linux-i2c
  Cc: oe-kbuild-all, andi.shyti, arnd, gregkh, Gerhard Engleder

Hi Gerhard,

kernel test robot noticed the following build warnings:

[auto build test WARNING on andi-shyti/i2c/i2c-host]
[also build test WARNING on char-misc/char-misc-testing char-misc/char-misc-next char-misc/char-misc-linus soc/for-next linus/master v6.10-rc1 next-20240531]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url:    https://github.com/intel-lab-lkp/linux/commits/Gerhard-Engleder/i2c-keba-Add-KEBA-I2C-controller-support/20240602-040548
base:   git://git.kernel.org/pub/scm/linux/kernel/git/andi.shyti/linux.git i2c/i2c-host
patch link:    https://lore.kernel.org/r/20240601192846.68146-2-gerhard%40engleder-embedded.com
patch subject: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
config: alpha-allyesconfig (https://download.01.org/0day-ci/archive/20240602/202406020634.cfpd5wMw-lkp@intel.com/config)
compiler: alpha-linux-gcc (GCC) 13.2.0
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240602/202406020634.cfpd5wMw-lkp@intel.com/reproduce)

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202406020634.cfpd5wMw-lkp@intel.com/

All warnings (new ones prefixed by >>):

>> drivers/i2c/busses/i2c-keba.c:568:34: warning: 'ki2c_devtype' defined but not used [-Wunused-variable]
     568 | static struct platform_device_id ki2c_devtype[] = {
         |                                  ^~~~~~~~~~~~


vim +/ki2c_devtype +568 drivers/i2c/busses/i2c-keba.c

   567	
 > 568	static struct platform_device_id ki2c_devtype[] = {
   569		{ .name = KI2C },
   570		{ }
   571	};
   572	MODULE_DEVICE_TABLE(platform, ki2c_devtype);
   573	

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

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

* Re: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
  2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
  2024-06-01 22:52   ` kernel test robot
@ 2024-06-01 23:45   ` kernel test robot
  2024-06-02 21:41   ` kernel test robot
                     ` (2 subsequent siblings)
  4 siblings, 0 replies; 13+ messages in thread
From: kernel test robot @ 2024-06-01 23:45 UTC (permalink / raw)
  To: Gerhard Engleder, linux-i2c
  Cc: llvm, oe-kbuild-all, andi.shyti, arnd, gregkh, Gerhard Engleder

Hi Gerhard,

kernel test robot noticed the following build warnings:

[auto build test WARNING on andi-shyti/i2c/i2c-host]
[also build test WARNING on char-misc/char-misc-testing char-misc/char-misc-next char-misc/char-misc-linus soc/for-next linus/master v6.10-rc1 next-20240531]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url:    https://github.com/intel-lab-lkp/linux/commits/Gerhard-Engleder/i2c-keba-Add-KEBA-I2C-controller-support/20240602-040548
base:   git://git.kernel.org/pub/scm/linux/kernel/git/andi.shyti/linux.git i2c/i2c-host
patch link:    https://lore.kernel.org/r/20240601192846.68146-2-gerhard%40engleder-embedded.com
patch subject: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
config: hexagon-allyesconfig (https://download.01.org/0day-ci/archive/20240602/202406020713.qwylbUoh-lkp@intel.com/config)
compiler: clang version 19.0.0git (https://github.com/llvm/llvm-project bafda89a0944d947fc4b3b5663185e07a397ac30)
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20240602/202406020713.qwylbUoh-lkp@intel.com/reproduce)

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202406020713.qwylbUoh-lkp@intel.com/

All warnings (new ones prefixed by >>):

   In file included from drivers/i2c/busses/i2c-keba.c:11:
   In file included from include/linux/io.h:14:
   In file included from arch/hexagon/include/asm/io.h:328:
   include/asm-generic/io.h:548:31: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
     548 |         val = __raw_readb(PCI_IOBASE + addr);
         |                           ~~~~~~~~~~ ^
   include/asm-generic/io.h:561:61: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
     561 |         val = __le16_to_cpu((__le16 __force)__raw_readw(PCI_IOBASE + addr));
         |                                                         ~~~~~~~~~~ ^
   include/uapi/linux/byteorder/little_endian.h:37:51: note: expanded from macro '__le16_to_cpu'
      37 | #define __le16_to_cpu(x) ((__force __u16)(__le16)(x))
         |                                                   ^
   In file included from drivers/i2c/busses/i2c-keba.c:11:
   In file included from include/linux/io.h:14:
   In file included from arch/hexagon/include/asm/io.h:328:
   include/asm-generic/io.h:574:61: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
     574 |         val = __le32_to_cpu((__le32 __force)__raw_readl(PCI_IOBASE + addr));
         |                                                         ~~~~~~~~~~ ^
   include/uapi/linux/byteorder/little_endian.h:35:51: note: expanded from macro '__le32_to_cpu'
      35 | #define __le32_to_cpu(x) ((__force __u32)(__le32)(x))
         |                                                   ^
   In file included from drivers/i2c/busses/i2c-keba.c:11:
   In file included from include/linux/io.h:14:
   In file included from arch/hexagon/include/asm/io.h:328:
   include/asm-generic/io.h:585:33: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
     585 |         __raw_writeb(value, PCI_IOBASE + addr);
         |                             ~~~~~~~~~~ ^
   include/asm-generic/io.h:595:59: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
     595 |         __raw_writew((u16 __force)cpu_to_le16(value), PCI_IOBASE + addr);
         |                                                       ~~~~~~~~~~ ^
   include/asm-generic/io.h:605:59: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
     605 |         __raw_writel((u32 __force)cpu_to_le32(value), PCI_IOBASE + addr);
         |                                                       ~~~~~~~~~~ ^
   In file included from drivers/i2c/busses/i2c-keba.c:13:
   In file included from include/linux/i2c.h:19:
   In file included from include/linux/regulator/consumer.h:35:
   In file included from include/linux/suspend.h:5:
   In file included from include/linux/swap.h:9:
   In file included from include/linux/memcontrol.h:21:
   In file included from include/linux/mm.h:2253:
   include/linux/vmstat.h:514:36: warning: arithmetic between different enumeration types ('enum node_stat_item' and 'enum lru_list') [-Wenum-enum-conversion]
     514 |         return node_stat_name(NR_LRU_BASE + lru) + 3; // skip "nr_"
         |                               ~~~~~~~~~~~ ^ ~~~
>> drivers/i2c/busses/i2c-keba.c:568:34: warning: unused variable 'ki2c_devtype' [-Wunused-variable]
     568 | static struct platform_device_id ki2c_devtype[] = {
         |                                  ^~~~~~~~~~~~
   8 warnings generated.


vim +/ki2c_devtype +568 drivers/i2c/busses/i2c-keba.c

   567	
 > 568	static struct platform_device_id ki2c_devtype[] = {
   569		{ .name = KI2C },
   570		{ }
   571	};
   572	MODULE_DEVICE_TABLE(platform, ki2c_devtype);
   573	

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

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

* Re: [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support
  2024-06-01 19:28 ` [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support Gerhard Engleder
@ 2024-06-02  7:19   ` Greg KH
  2024-06-02 18:59     ` Gerhard Engleder
  2024-06-02 23:37   ` kernel test robot
  2024-06-04  5:13   ` kernel test robot
  2 siblings, 1 reply; 13+ messages in thread
From: Greg KH @ 2024-06-02  7:19 UTC (permalink / raw)
  To: Gerhard Engleder; +Cc: linux-i2c, andi.shyti, arnd, Gerhard Engleder

On Sat, Jun 01, 2024 at 09:28:46PM +0200, Gerhard Engleder wrote:
> From: Gerhard Engleder <eg@keba.com>
> 
> The KEBA CP500 system FPGA is a PCIe device, which consists of multiple
> IP cores. Every IP core has its own platform driver. The cp500 driver
> registers a platform device for each device and the corresponding
> drivers are loaded by the Linux driver infrastructure.

Please use the aux bus code for this, not the platform driver code.
That's what the aux bus is explicitly for, platform devices are NOT
meant to hang off of a PCIe device at all.

> Currently 3 variants of this device exists. Every variant has its own
> PCI device ID, which is used to determine the list of available IP
> cores. In this first version only the platform device for the I2C
> controller is registered.
> 
> Besides the platform device registration some other basic functions of
> the FPGA are implemented; e.g, FPGA version sysfs file, keep FPGA
> configuration on reset sysfs file, error message for errors on the
> internal AXI bus of the FPGA.
> 
> Signed-off-by: Gerhard Engleder <eg@keba.com>
> ---
>  drivers/misc/Kconfig       |   1 +
>  drivers/misc/Makefile      |   1 +
>  drivers/misc/keba/Kconfig  |  12 +
>  drivers/misc/keba/Makefile |   3 +
>  drivers/misc/keba/cp500.c  | 433 +++++++++++++++++++++++++++++++++++++
>  5 files changed, 450 insertions(+)
>  create mode 100644 drivers/misc/keba/Kconfig
>  create mode 100644 drivers/misc/keba/Makefile
>  create mode 100644 drivers/misc/keba/cp500.c

You create sysfs files for this driver, yet there is no
Documentation/ABI/ entries for it?  Please do so in your next version of
this series.

> +static ssize_t keep_cfg_show(struct device *dev, struct device_attribute *attr,
> +			     char *buf)
> +{
> +	struct cp500 *cp500 = dev_get_drvdata(dev);
> +	unsigned long keep_cfg = 1;
> +
> +	/* FPGA configuration stream is kept during reset when RECONFIG bit is
> +	 * zero
> +	 */
> +	if (ioread8(cp500->system_startup_addr + CP500_RECONFIG_REG) &
> +		CP500_RECFG_REQ)
> +		keep_cfg = 0;
> +
> +	return sprintf(buf, "%lu\n", keep_cfg);

sysfs_emit() for all sysfs show functions please.

thanks,

greg k-h

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

* Re: [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support
  2024-06-02  7:19   ` Greg KH
@ 2024-06-02 18:59     ` Gerhard Engleder
  0 siblings, 0 replies; 13+ messages in thread
From: Gerhard Engleder @ 2024-06-02 18:59 UTC (permalink / raw)
  To: Greg KH; +Cc: linux-i2c, andi.shyti, arnd, Gerhard Engleder

On 02.06.24 09:19, Greg KH wrote:
> On Sat, Jun 01, 2024 at 09:28:46PM +0200, Gerhard Engleder wrote:
>> From: Gerhard Engleder <eg@keba.com>
>>
>> The KEBA CP500 system FPGA is a PCIe device, which consists of multiple
>> IP cores. Every IP core has its own platform driver. The cp500 driver
>> registers a platform device for each device and the corresponding
>> drivers are loaded by the Linux driver infrastructure.
> 
> Please use the aux bus code for this, not the platform driver code.
> That's what the aux bus is explicitly for, platform devices are NOT
> meant to hang off of a PCIe device at all.

Thank you for that advice! I was not aware of aux bus, but it seems to
be a good fit.

>> Currently 3 variants of this device exists. Every variant has its own
>> PCI device ID, which is used to determine the list of available IP
>> cores. In this first version only the platform device for the I2C
>> controller is registered.
>>
>> Besides the platform device registration some other basic functions of
>> the FPGA are implemented; e.g, FPGA version sysfs file, keep FPGA
>> configuration on reset sysfs file, error message for errors on the
>> internal AXI bus of the FPGA.
>>
>> Signed-off-by: Gerhard Engleder <eg@keba.com>
>> ---
>>   drivers/misc/Kconfig       |   1 +
>>   drivers/misc/Makefile      |   1 +
>>   drivers/misc/keba/Kconfig  |  12 +
>>   drivers/misc/keba/Makefile |   3 +
>>   drivers/misc/keba/cp500.c  | 433 +++++++++++++++++++++++++++++++++++++
>>   5 files changed, 450 insertions(+)
>>   create mode 100644 drivers/misc/keba/Kconfig
>>   create mode 100644 drivers/misc/keba/Makefile
>>   create mode 100644 drivers/misc/keba/cp500.c
> 
> You create sysfs files for this driver, yet there is no
> Documentation/ABI/ entries for it?  Please do so in your next version of
> this series.

I will do so.
>> +static ssize_t keep_cfg_show(struct device *dev, struct device_attribute *attr,
>> +			     char *buf)
>> +{
>> +	struct cp500 *cp500 = dev_get_drvdata(dev);
>> +	unsigned long keep_cfg = 1;
>> +
>> +	/* FPGA configuration stream is kept during reset when RECONFIG bit is
>> +	 * zero
>> +	 */
>> +	if (ioread8(cp500->system_startup_addr + CP500_RECONFIG_REG) &
>> +		CP500_RECFG_REQ)
>> +		keep_cfg = 0;
>> +
>> +	return sprintf(buf, "%lu\n", keep_cfg);
> 
> sysfs_emit() for all sysfs show functions please.

sysfs_emit() will be used.


Thank you for your feedback!

gerhard

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

* Re: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
  2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
  2024-06-01 22:52   ` kernel test robot
  2024-06-01 23:45   ` kernel test robot
@ 2024-06-02 21:41   ` kernel test robot
  2024-06-03 22:37   ` Andi Shyti
  2024-06-03 23:00   ` kernel test robot
  4 siblings, 0 replies; 13+ messages in thread
From: kernel test robot @ 2024-06-02 21:41 UTC (permalink / raw)
  To: Gerhard Engleder, linux-i2c
  Cc: oe-kbuild-all, andi.shyti, arnd, gregkh, Gerhard Engleder

Hi Gerhard,

kernel test robot noticed the following build warnings:

[auto build test WARNING on andi-shyti/i2c/i2c-host]
[also build test WARNING on char-misc/char-misc-testing char-misc/char-misc-next char-misc/char-misc-linus soc/for-next linus/master v6.10-rc1 next-20240531]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url:    https://github.com/intel-lab-lkp/linux/commits/Gerhard-Engleder/i2c-keba-Add-KEBA-I2C-controller-support/20240602-040548
base:   git://git.kernel.org/pub/scm/linux/kernel/git/andi.shyti/linux.git i2c/i2c-host
patch link:    https://lore.kernel.org/r/20240601192846.68146-2-gerhard%40engleder-embedded.com
patch subject: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
config: s390-randconfig-r062-20240603 (https://download.01.org/0day-ci/archive/20240603/202406030504.QcIr6Qaw-lkp@intel.com/config)
compiler: s390-linux-gcc (GCC) 13.2.0

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202406030504.QcIr6Qaw-lkp@intel.com/

cocci warnings: (new ones prefixed by >>)
>> drivers/i2c/busses/i2c-keba.c:491:14-15: WARNING comparing pointer to 0

vim +491 drivers/i2c/busses/i2c-keba.c

   480	
   481	static int ki2c_probe(struct platform_device *pdev)
   482	{
   483		struct i2c_keba_platform_data *pdata;
   484		struct device *dev = &pdev->dev;
   485		struct i2c_adapter *adap;
   486		struct resource *io;
   487		struct ki2c *ki2c;
   488		int ret;
   489	
   490		pdata = dev->platform_data;
 > 491		if (pdata == 0) {
   492			dev_err(dev, "Platform data not found!\n");
   493			return -ENODEV;
   494		}
   495	
   496		ki2c = devm_kzalloc(dev, sizeof(*ki2c), GFP_KERNEL);
   497		if (!ki2c)
   498			return -ENOMEM;
   499		ki2c->pdev = pdev;
   500		ki2c->client = devm_kcalloc(dev, pdata->info_size,
   501					    sizeof(*ki2c->client), GFP_KERNEL);
   502		if (!ki2c->client)
   503			return -ENOMEM;
   504		ki2c->client_size = pdata->info_size;
   505		platform_set_drvdata(pdev, ki2c);
   506	
   507		io = platform_get_resource(pdev, IORESOURCE_MEM, 0);
   508		ki2c->base = devm_ioremap_resource(dev, io);
   509		if (IS_ERR(ki2c->base))
   510			return PTR_ERR(ki2c->base);
   511	
   512		/* enable controller */
   513		iowrite8(KI2C_CONTROL_MEN, ki2c->base + KI2C_CONTROL_REG);
   514	
   515		adap = &ki2c->adapter;
   516		strscpy(adap->name, "KEBA I2C adapter", sizeof(adap->name));
   517		adap->owner = THIS_MODULE;
   518		adap->class = I2C_CLASS_HWMON;
   519		adap->algo = &ki2c_algo;
   520		adap->dev.parent = dev;
   521	
   522		i2c_set_adapdata(adap, ki2c);
   523	
   524		/* reset bus before probing I2C devices */
   525		ret = ki2c_reset_bus(ki2c);
   526		if (ret) {
   527			dev_err(dev, "Failed to reset bus (%d)!\n", ret);
   528			goto out_disable;
   529		}
   530	
   531		ret = i2c_add_adapter(adap);
   532		if (ret) {
   533			dev_err(dev, "Failed to add adapter (%d)!\n", ret);
   534			goto out_disable;
   535		}
   536	
   537		ret = ki2c_register_devices(ki2c, pdata);
   538		if (ret) {
   539			dev_err(dev, "Failed to register devices (%d)!\n", ret);
   540			goto out_delete;
   541		}
   542	
   543		return 0;
   544	
   545	out_delete:
   546		i2c_del_adapter(adap);
   547	out_disable:
   548		iowrite8(0, ki2c->base + KI2C_CONTROL_REG);
   549		return ret;
   550	}
   551	

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

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

* Re: [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support
  2024-06-01 19:28 ` [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support Gerhard Engleder
  2024-06-02  7:19   ` Greg KH
@ 2024-06-02 23:37   ` kernel test robot
  2024-06-04  5:13   ` kernel test robot
  2 siblings, 0 replies; 13+ messages in thread
From: kernel test robot @ 2024-06-02 23:37 UTC (permalink / raw)
  To: Gerhard Engleder, linux-i2c
  Cc: oe-kbuild-all, andi.shyti, arnd, gregkh, Gerhard Engleder

Hi Gerhard,

kernel test robot noticed the following build warnings:

[auto build test WARNING on andi-shyti/i2c/i2c-host]
[also build test WARNING on char-misc/char-misc-testing char-misc/char-misc-next char-misc/char-misc-linus soc/for-next linus/master v6.10-rc1 next-20240531]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url:    https://github.com/intel-lab-lkp/linux/commits/Gerhard-Engleder/i2c-keba-Add-KEBA-I2C-controller-support/20240602-040548
base:   git://git.kernel.org/pub/scm/linux/kernel/git/andi.shyti/linux.git i2c/i2c-host
patch link:    https://lore.kernel.org/r/20240601192846.68146-3-gerhard%40engleder-embedded.com
patch subject: [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support
config: s390-randconfig-r062-20240603 (https://download.01.org/0day-ci/archive/20240603/202406030714.6PytC3El-lkp@intel.com/config)
compiler: s390-linux-gcc (GCC) 13.2.0

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202406030714.6PytC3El-lkp@intel.com/

cocci warnings: (new ones prefixed by >>)
>> drivers/misc/keba/cp500.c:324:14-15: WARNING comparing pointer to 0

vim +324 drivers/misc/keba/cp500.c

   313	
   314	static int cp500_probe(struct pci_dev *pci_dev, const struct pci_device_id *id)
   315	{
   316		struct device *dev = &pci_dev->dev;
   317		struct resource startup;
   318		struct cp500 *cp500;
   319		u32 cp500_vers;
   320		char buf[64];
   321		int ret;
   322	
   323		cp500 = devm_kzalloc(dev, sizeof(*cp500), GFP_KERNEL);
 > 324		if (cp500 == 0)
   325			return -ENOMEM;
   326		cp500->pci_dev = pci_dev;
   327		cp500->sys_hwbase = pci_resource_start(pci_dev, CP500_SYS_BAR);
   328		cp500->ecm_hwbase = pci_resource_start(pci_dev, CP500_ECM_BAR);
   329		if (!cp500->sys_hwbase || !cp500->ecm_hwbase)
   330			return -ENODEV;
   331	
   332		if (CP500_IS_CP035(cp500))
   333			cp500->devs = &cp035_devices;
   334		else if (CP500_IS_CP505(cp500))
   335			cp500->devs = &cp505_devices;
   336		else if (CP500_IS_CP520(cp500))
   337			cp500->devs = &cp520_devices;
   338		else
   339			return -ENODEV;
   340	
   341		ret = pci_enable_device(pci_dev);
   342		if (ret)
   343			return ret;
   344		pci_set_master(pci_dev);
   345	
   346		startup = *pci_resource_n(pci_dev, CP500_SYS_BAR);
   347		startup.end = startup.start + cp500->devs->startup.size - 1;
   348		cp500->system_startup_addr = devm_ioremap_resource(&pci_dev->dev,
   349								   &startup);
   350		if (IS_ERR(cp500->system_startup_addr)) {
   351			ret = PTR_ERR(cp500->system_startup_addr);
   352			goto out_disable;
   353		}
   354	
   355		cp500->msix_num = pci_alloc_irq_vectors(pci_dev, CP500_NUM_MSIX_NO_MMI,
   356							CP500_NUM_MSIX, PCI_IRQ_MSIX);
   357		if (cp500->msix_num < CP500_NUM_MSIX_NO_MMI) {
   358			dev_err(&pci_dev->dev,
   359				"Hardware does not support enough MSI-X interrupts\n");
   360			ret = -ENODEV;
   361			goto out_disable;
   362		}
   363	
   364		cp500_vers = ioread32(cp500->system_startup_addr + CP500_VERSION_REG);
   365		cp500->version.major = (cp500_vers & 0xff);
   366		cp500->version.minor = (cp500_vers >> 8) & 0xff;
   367		cp500->version.build = (cp500_vers >> 16) & 0xffff;
   368		cp500_get_fpga_version(cp500, buf, sizeof(buf));
   369	
   370		dev_info(&pci_dev->dev, "FPGA version %s", buf);
   371	
   372		pci_set_drvdata(pci_dev, cp500);
   373	
   374		ret = sysfs_create_group(&pci_dev->dev.kobj, &attrs_group);
   375		if (ret != 0)
   376			goto out_free_irq;
   377	
   378		ret = cp500_enable(cp500);
   379		if (ret != 0)
   380			goto out_remove_group;
   381	
   382		cp500_register_platform_devs(cp500);
   383	
   384		return 0;
   385	
   386	out_remove_group:
   387		sysfs_remove_group(&pci_dev->dev.kobj, &attrs_group);
   388	out_free_irq:
   389		pci_free_irq_vectors(pci_dev);
   390	out_disable:
   391		pci_clear_master(pci_dev);
   392		pci_disable_device(pci_dev);
   393	
   394		return ret;
   395	}
   396	

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

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

* Re: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
  2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
                     ` (2 preceding siblings ...)
  2024-06-02 21:41   ` kernel test robot
@ 2024-06-03 22:37   ` Andi Shyti
  2024-06-04 19:06     ` Gerhard Engleder
  2024-06-03 23:00   ` kernel test robot
  4 siblings, 1 reply; 13+ messages in thread
From: Andi Shyti @ 2024-06-03 22:37 UTC (permalink / raw)
  To: Gerhard Engleder; +Cc: linux-i2c, arnd, gregkh, Gerhard Engleder

Hi Gerhard,

On Sat, Jun 01, 2024 at 09:28:45PM +0200, Gerhard Engleder wrote:
> From: Gerhard Engleder <eg@keba.com>
> 
> The KEBA I2C controller is found in the system FPGA of KEBA PLC devices.
> It is used to connect EEPROMs and hardware monitoring chips.

can you please add more information about the device, please?

...

> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * Copyright (C) KEBA AG 2012

can we update the date here?

> + * Copyright (C) KEBA Industrial Automation Gmbh 2024
> + *
> + * Driver for KEBA I2C controller FPGA IP core
> + */
> +
> +#include <linux/module.h>
> +#include <linux/platform_device.h>
> +#include <linux/io.h>
> +#include <linux/iopoll.h>
> +#include <linux/i2c.h>
> +#include <linux/platform_data/i2c-keba.h>

Can you sort them in alphabetical order, please?

> +#define KI2C "i2c-keba"
> +
> +#define KI2C_CAPABILITY_REG	0x02
> +#define KI2C_CONTROL_REG	0x04
> +#define KI2C_CONTROL_DC_REG	0x05
> +#define KI2C_STATUS_REG		0x08
> +#define KI2C_STATUS_DC_REG	0x09
> +#define KI2C_DATA_REG		0x0c
> +
> +#define KI2C_CAPABILITY_CRYPTO	0x01

This crypto is not used anywhere, did you add it for completness
or have you forgotten to use it?

> +#define KI2C_CAPABILITY_DC	0x02
> +
> +#define KI2C_CONTROL_MEN	0x01
> +#define KI2C_CONTROL_MSTA	0x02
> +#define KI2C_CONTROL_RSTA	0x04
> +#define KI2C_CONTROL_MTX	0x08
> +#define KI2C_CONTROL_TXAK	0x10
> +
> +#define KI2C_STATUS_IN_USE	0x01
> +#define KI2C_STATUS_ACK_CYC	0x02
> +#define KI2C_STATUS_RXAK	0x04
> +#define KI2C_STATUS_MCF		0x08
> +
> +#define KI2C_DC_SDA		0x01
> +#define KI2C_DC_SCL		0x02

You could eventually make it as:

#define REG1_ADDR	0xXX
#define   REG1_VAL_1	0xXX
#define   REG1_VAL_2	0xXX
#define   REG1_VAL_3	0xXX

#define REG2_ADDR	0xXX
#define   REG2_VAL_1	0xXX
#define   REG2_VAL_2	0xXX
#define   REG2_VAL_3	0xXX

So that it's clear what belongs to what. Not a binding comment,
just an aesthetic note.

> +
> +#define KI2C_INUSE_SLEEP_US	(2 * USEC_PER_MSEC)
> +#define KI2C_INUSE_TIMEOUT_US	(10 * USEC_PER_SEC)
> +
> +#define KI2C_POLL_DELAY_US	5
> +
> +struct ki2c {
> +	struct platform_device *pdev;
> +	void __iomem *base;
> +	struct i2c_adapter adapter;
> +
> +	struct i2c_client **client;
> +	int client_size;
> +};
> +
> +static int ki2c_inuse_lock(struct ki2c *ki2c)
> +{
> +	u8 sts;
> +	int ret;
> +
> +	/* The I2C controller has an IN_USE bit for locking access to the
> +	 * controller. This enables the use of I2C controller by other none
> +	 * Linux processors.

Please use the proper commenting style:

	/*
	 * Comment line 1
	 * Comment line 2
	 * ...
	 * Comment line N
	 */

> +	 *
> +	 * If the I2C controller is free, then the first read returns
> +	 * IN_USE == 0. After that the I2C controller is locked and further
> +	 * reads of IN_USE return 1.
> +	 *
> +	 * The I2C controller is unlocked by writing 1 into IN_USE.
> +	 */

Basically this is a semaphore.

> +	ret = readb_poll_timeout(ki2c->base + KI2C_STATUS_REG,
> +				 sts, (sts & KI2C_STATUS_IN_USE) == 0,
> +				 KI2C_INUSE_SLEEP_US, KI2C_INUSE_TIMEOUT_US);

we are waiting too long here... the documentaition recommends to
use the readb_poll_timeout for less than 10us, while we are
waiting 2ms.

> +	if (ret != 0)
> +		dev_warn(&ki2c->pdev->dev, "%s err!\n", __func__);
> +
> +	return ret;
> +}
> +
> +static void ki2c_inuse_unlock(struct ki2c *ki2c)
> +{
> +	/* unlock the controller by writing 1 into IN_USE */
> +	iowrite8(KI2C_STATUS_IN_USE, ki2c->base + KI2C_STATUS_REG);
> +}
> +
> +static int ki2c_wait_for_bit(u8 mask, void __iomem *addr, unsigned long timeout)

It looks more natural to have "addr" as a first argument.

> +{
> +	u8 val;
> +
> +	return readb_poll_timeout(addr, val, (val & mask), KI2C_POLL_DELAY_US,
> +				  jiffies_to_usecs(timeout));
> +}
> +static int ki2c_get_sda(struct ki2c *ki2c)
> +{
> +	/* capability KI2C_CAPABILITY_DC required */
> +	return (ioread8(ki2c->base + KI2C_STATUS_DC_REG) & KI2C_DC_SDA) != 0;

Please avoid using such compact style.

> +}
> +	/* generate clock cycles */
> +	ki2c_set_scl(ki2c, val);
> +	ndelay(KI2C_RECOVERY_NDELAY);
> +	while (count++ < KI2C_RECOVERY_CLK_CNT * 2) {
> +		if (val) {
> +			/* SCL shouldn't be low here */
> +			if (!ki2c_get_scl(ki2c)) {
> +				dev_err(&ki2c->pdev->dev,
> +					"SCL is stuck low!\n");
> +				ret = -EBUSY;
> +				break;
> +			}
> +
> +			/* break if SDA is high */
> +			if (ki2c_get_sda(ki2c))
> +				break;
> +		}
> +
> +		val = !val;
> +		ki2c_set_scl(ki2c, val);
> +		ndelay(KI2C_RECOVERY_NDELAY);

I don't know how much sense it makes to wait in ndelays, this is
not going to be precise and... are we sure we want to wait
atomically here?

> +	}
> +
> +	if (!ki2c_get_sda(ki2c)) {
> +		dev_err(&ki2c->pdev->dev, "SDA is still low!\n");

To me this and the above dev_err's are just spamming the dmesg as
we are already printing up in the probe function. If we want to
have more precision printing, then we need to chose where the
dev_err's need to be.

> +		ret = -EBUSY;
> +	}
> +
> +	/* reenable controller */
> +	iowrite8(KI2C_CONTROL_MEN, ki2c->base + KI2C_CONTROL_REG);

...

> +	ret = ki2c_wait_for_data_ack(ki2c);
> +	if (ret < 0)
> +		/* For EEPROMs this is normal behavior during internal write
> +		 * operation.

Please, mind the coding style.

> +		 */
> +		dev_dbg(&ki2c->pdev->dev, "%s wait for ACK err at 0x%02x!\n",
> +			__func__, m->addr);
> +
> +	return ret;
> +}

...

> +static int ki2c_probe(struct platform_device *pdev)
> +{
> +	struct i2c_keba_platform_data *pdata;
> +	struct device *dev = &pdev->dev;
> +	struct i2c_adapter *adap;
> +	struct resource *io;
> +	struct ki2c *ki2c;
> +	int ret;
> +
> +	pdata = dev->platform_data;
> +	if (pdata == 0) {
> +		dev_err(dev, "Platform data not found!\n");
> +		return -ENODEV;

please use dev_err_probe()

Andi

...

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

* Re: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
  2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
                     ` (3 preceding siblings ...)
  2024-06-03 22:37   ` Andi Shyti
@ 2024-06-03 23:00   ` kernel test robot
  4 siblings, 0 replies; 13+ messages in thread
From: kernel test robot @ 2024-06-03 23:00 UTC (permalink / raw)
  To: Gerhard Engleder, linux-i2c
  Cc: oe-kbuild-all, andi.shyti, arnd, gregkh, Gerhard Engleder

Hi Gerhard,

kernel test robot noticed the following build warnings:

[auto build test WARNING on andi-shyti/i2c/i2c-host]
[also build test WARNING on char-misc/char-misc-testing char-misc/char-misc-next char-misc/char-misc-linus soc/for-next linus/master v6.10-rc2 next-20240603]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url:    https://github.com/intel-lab-lkp/linux/commits/Gerhard-Engleder/i2c-keba-Add-KEBA-I2C-controller-support/20240602-040548
base:   git://git.kernel.org/pub/scm/linux/kernel/git/andi.shyti/linux.git i2c/i2c-host
patch link:    https://lore.kernel.org/r/20240601192846.68146-2-gerhard%40engleder-embedded.com
patch subject: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
config: csky-randconfig-r121-20240604 (https://download.01.org/0day-ci/archive/20240604/202406040659.nZr6W80c-lkp@intel.com/config)
compiler: csky-linux-gcc (GCC) 13.2.0
reproduce: (https://download.01.org/0day-ci/archive/20240604/202406040659.nZr6W80c-lkp@intel.com/reproduce)

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202406040659.nZr6W80c-lkp@intel.com/

sparse warnings: (new ones prefixed by >>)
>> drivers/i2c/busses/i2c-keba.c:491:22: sparse: sparse: Using plain integer as NULL pointer
   drivers/i2c/busses/i2c-keba.c:563:36: sparse: sparse: Using plain integer as NULL pointer

vim +491 drivers/i2c/busses/i2c-keba.c

   480	
   481	static int ki2c_probe(struct platform_device *pdev)
   482	{
   483		struct i2c_keba_platform_data *pdata;
   484		struct device *dev = &pdev->dev;
   485		struct i2c_adapter *adap;
   486		struct resource *io;
   487		struct ki2c *ki2c;
   488		int ret;
   489	
   490		pdata = dev->platform_data;
 > 491		if (pdata == 0) {
   492			dev_err(dev, "Platform data not found!\n");
   493			return -ENODEV;
   494		}
   495	
   496		ki2c = devm_kzalloc(dev, sizeof(*ki2c), GFP_KERNEL);
   497		if (!ki2c)
   498			return -ENOMEM;
   499		ki2c->pdev = pdev;
   500		ki2c->client = devm_kcalloc(dev, pdata->info_size,
   501					    sizeof(*ki2c->client), GFP_KERNEL);
   502		if (!ki2c->client)
   503			return -ENOMEM;
   504		ki2c->client_size = pdata->info_size;
   505		platform_set_drvdata(pdev, ki2c);
   506	
   507		io = platform_get_resource(pdev, IORESOURCE_MEM, 0);
   508		ki2c->base = devm_ioremap_resource(dev, io);
   509		if (IS_ERR(ki2c->base))
   510			return PTR_ERR(ki2c->base);
   511	
   512		/* enable controller */
   513		iowrite8(KI2C_CONTROL_MEN, ki2c->base + KI2C_CONTROL_REG);
   514	
   515		adap = &ki2c->adapter;
   516		strscpy(adap->name, "KEBA I2C adapter", sizeof(adap->name));
   517		adap->owner = THIS_MODULE;
   518		adap->class = I2C_CLASS_HWMON;
   519		adap->algo = &ki2c_algo;
   520		adap->dev.parent = dev;
   521	
   522		i2c_set_adapdata(adap, ki2c);
   523	
   524		/* reset bus before probing I2C devices */
   525		ret = ki2c_reset_bus(ki2c);
   526		if (ret) {
   527			dev_err(dev, "Failed to reset bus (%d)!\n", ret);
   528			goto out_disable;
   529		}
   530	
   531		ret = i2c_add_adapter(adap);
   532		if (ret) {
   533			dev_err(dev, "Failed to add adapter (%d)!\n", ret);
   534			goto out_disable;
   535		}
   536	
   537		ret = ki2c_register_devices(ki2c, pdata);
   538		if (ret) {
   539			dev_err(dev, "Failed to register devices (%d)!\n", ret);
   540			goto out_delete;
   541		}
   542	
   543		return 0;
   544	
   545	out_delete:
   546		i2c_del_adapter(adap);
   547	out_disable:
   548		iowrite8(0, ki2c->base + KI2C_CONTROL_REG);
   549		return ret;
   550	}
   551	

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

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

* Re: [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support
  2024-06-01 19:28 ` [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support Gerhard Engleder
  2024-06-02  7:19   ` Greg KH
  2024-06-02 23:37   ` kernel test robot
@ 2024-06-04  5:13   ` kernel test robot
  2 siblings, 0 replies; 13+ messages in thread
From: kernel test robot @ 2024-06-04  5:13 UTC (permalink / raw)
  To: Gerhard Engleder, linux-i2c
  Cc: oe-kbuild-all, andi.shyti, arnd, gregkh, Gerhard Engleder

Hi Gerhard,

kernel test robot noticed the following build warnings:

[auto build test WARNING on andi-shyti/i2c/i2c-host]
[also build test WARNING on char-misc/char-misc-testing char-misc/char-misc-next char-misc/char-misc-linus soc/for-next linus/master v6.10-rc2 next-20240603]
[If your patch is applied to the wrong git tree, kindly drop us a note.
And when submitting patch, we suggest to use '--base' as documented in
https://git-scm.com/docs/git-format-patch#_base_tree_information]

url:    https://github.com/intel-lab-lkp/linux/commits/Gerhard-Engleder/i2c-keba-Add-KEBA-I2C-controller-support/20240602-040548
base:   git://git.kernel.org/pub/scm/linux/kernel/git/andi.shyti/linux.git i2c/i2c-host
patch link:    https://lore.kernel.org/r/20240601192846.68146-3-gerhard%40engleder-embedded.com
patch subject: [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support
config: csky-randconfig-r132-20240604 (https://download.01.org/0day-ci/archive/20240604/202406041218.9TKBWHf2-lkp@intel.com/config)
compiler: csky-linux-gcc (GCC) 13.2.0
reproduce: (https://download.01.org/0day-ci/archive/20240604/202406041218.9TKBWHf2-lkp@intel.com/reproduce)

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202406041218.9TKBWHf2-lkp@intel.com/

sparse warnings: (new ones prefixed by >>)
>> drivers/misc/keba/cp500.c:64:19: sparse: sparse: symbol 'cp035_devices' was not declared. Should it be static?
>> drivers/misc/keba/cp500.c:70:19: sparse: sparse: symbol 'cp505_devices' was not declared. Should it be static?
>> drivers/misc/keba/cp500.c:76:19: sparse: sparse: symbol 'cp520_devices' was not declared. Should it be static?
>> drivers/misc/keba/cp500.c:262:26: sparse: sparse: Using plain integer as NULL pointer
   drivers/misc/keba/cp500.c:324:22: sparse: sparse: Using plain integer as NULL pointer
   drivers/misc/keba/cp500.c:407:34: sparse: sparse: Using plain integer as NULL pointer
   drivers/misc/keba/cp500.c: note: in included file (through include/linux/mmzone.h, include/linux/gfp.h, include/linux/xarray.h, ...):
   include/linux/page-flags.h:240:46: sparse: sparse: self-comparison always evaluates to false
   include/linux/page-flags.h:240:46: sparse: sparse: self-comparison always evaluates to false

vim +/cp035_devices +64 drivers/misc/keba/cp500.c

    62	
    63	/* list of devices within FPGA of CP035 family (CP035, CP056, CP057) */
  > 64	struct cp500_devs cp035_devices = {
    65		.startup   = { 0x0000, SZ_4K },
    66		.i2c       = { 0x4000, SZ_4K },
    67	};
    68	
    69	/* list of devices within FPGA of CP505 family (CP503, CP505, CP507) */
  > 70	struct cp500_devs cp505_devices = {
    71		.startup   = { 0x0000, SZ_4K },
    72		.i2c       = { 0x5000, SZ_4K },
    73	};
    74	
    75	/* list of devices within FPGA of CP520 family (CP520, CP530) */
  > 76	struct cp500_devs cp520_devices = {
    77		.startup     = { 0x0000, SZ_4K },
    78		.i2c         = { 0x5000, SZ_4K },
    79	};
    80	
    81	struct cp500 {
    82		struct pci_dev *pci_dev;
    83		struct cp500_devs *devs;
    84		int msix_num;
    85		struct {
    86			int major;
    87			int minor;
    88			int build;
    89		} version;
    90	
    91		/* system FPGA BAR */
    92		resource_size_t sys_hwbase;
    93		struct platform_device *i2c;
    94	
    95		/* ECM EtherCAT BAR */
    96		resource_size_t ecm_hwbase;
    97	
    98		void __iomem *system_startup_addr;
    99	};
   100	
   101	/* I2C devices */
   102	static struct i2c_board_info cp500_i2c_info[] = {
   103		{	/* temperature sensor */
   104			I2C_BOARD_INFO("emc1403", 0x4c),
   105		},
   106		{	/* CPU EEPROM
   107			 * CP035 family: CPU board
   108			 * CP505 family: bridge board
   109			 * CP520 family: carrier board
   110			 */
   111			I2C_BOARD_INFO("24c32", 0x50),
   112			.dev_name = CP500_HW_CPU_EEPROM_NAME,
   113		},
   114		{	/* interface board EEPROM */
   115			I2C_BOARD_INFO("24c32", 0x51),
   116		},
   117		{	/* EEPROM (optional)
   118			 * CP505 family: CPU board
   119			 * CP520 family: MMI board
   120			 */
   121			I2C_BOARD_INFO("24c32", 0x52),
   122		},
   123		{	/* extension module 0 EEPROM (optional) */
   124			I2C_BOARD_INFO("24c32", 0x53),
   125		},
   126		{	/* extension module 1 EEPROM (optional) */
   127			I2C_BOARD_INFO("24c32", 0x54),
   128		},
   129		{	/* extension module 2 EEPROM (optional) */
   130			I2C_BOARD_INFO("24c32", 0x55),
   131		},
   132		{	/* extension module 3 EEPROM (optional) */
   133			I2C_BOARD_INFO("24c32", 0x56),
   134		}
   135	};
   136	
   137	static ssize_t cp500_get_fpga_version(struct cp500 *cp500, char *buf,
   138					      size_t max_len)
   139	{
   140		int n;
   141	
   142		if (CP500_IS_CP035(cp500))
   143			n = scnprintf(buf, max_len, "CP035");
   144		else if (CP500_IS_CP505(cp500))
   145			n = scnprintf(buf, max_len, "CP505");
   146		else
   147			n = scnprintf(buf, max_len, "CP500");
   148	
   149		n += scnprintf(buf + n, max_len - n, "_FPGA_%d.%02d",
   150			       cp500->version.major, cp500->version.minor);
   151	
   152		/* test versions have test bit set */
   153		if (cp500->version.build & CP500_BUILD_TEST)
   154			n += scnprintf(buf + n, max_len - n, "Test%d",
   155				       cp500->version.build & ~CP500_BUILD_TEST);
   156	
   157		n += scnprintf(buf + n, max_len - n, "\n");
   158	
   159		return n;
   160	}
   161	
   162	static ssize_t version_show(struct device *dev, struct device_attribute *attr,
   163				    char *buf)
   164	{
   165		struct cp500 *cp500 = dev_get_drvdata(dev);
   166	
   167		return cp500_get_fpga_version(cp500, buf, PAGE_SIZE);
   168	}
   169	static DEVICE_ATTR_RO(version);
   170	
   171	static ssize_t keep_cfg_show(struct device *dev, struct device_attribute *attr,
   172				     char *buf)
   173	{
   174		struct cp500 *cp500 = dev_get_drvdata(dev);
   175		unsigned long keep_cfg = 1;
   176	
   177		/* FPGA configuration stream is kept during reset when RECONFIG bit is
   178		 * zero
   179		 */
   180		if (ioread8(cp500->system_startup_addr + CP500_RECONFIG_REG) &
   181			CP500_RECFG_REQ)
   182			keep_cfg = 0;
   183	
   184		return sprintf(buf, "%lu\n", keep_cfg);
   185	}
   186	
   187	static ssize_t keep_cfg_store(struct device *dev, struct device_attribute *attr,
   188				      const char *buf, size_t count)
   189	{
   190		struct cp500 *cp500 = dev_get_drvdata(dev);
   191		unsigned long keep_cfg;
   192	
   193		if (kstrtoul(buf, 10, &keep_cfg) < 0)
   194			return -EINVAL;
   195	
   196		/* In normal operation "keep_cfg" is "1". This means that the FPGA keeps
   197		 * its configuration stream during a reset.
   198		 * In case of a firmware update of the FPGA, the configuration stream
   199		 * needs to be reloaded. This can be done without a powercycle by
   200		 * writing a "0" into the "keep_cfg" attribute. After a reset/reboot th
   201		 * new configuration stream will be loaded.
   202		 */
   203		if (keep_cfg)
   204			iowrite8(0, cp500->system_startup_addr + CP500_RECONFIG_REG);
   205		else
   206			iowrite8(CP500_RECFG_REQ,
   207				 cp500->system_startup_addr + CP500_RECONFIG_REG);
   208	
   209		return count;
   210	}
   211	static DEVICE_ATTR_RW(keep_cfg);
   212	
   213	static struct attribute *attrs[] = {
   214		&dev_attr_version.attr,
   215		&dev_attr_keep_cfg.attr,
   216		NULL
   217	};
   218	static const struct attribute_group attrs_group = { .attrs = attrs };
   219	
   220	static int cp500_register_i2c(struct cp500 *cp500)
   221	{
   222		struct i2c_keba_platform_data data;
   223		struct platform_device *pdev;
   224		struct resource res[] = {
   225			{
   226			 /* I2C register area */
   227			 .start = (resource_size_t) cp500->sys_hwbase +
   228				  cp500->devs->i2c.offset,
   229			 .end   = (resource_size_t) cp500->sys_hwbase +
   230				  cp500->devs->i2c.offset +
   231				  cp500->devs->i2c.size - 1,
   232			 .flags = IORESOURCE_MEM,
   233			 },
   234		};
   235	
   236		data.info = cp500_i2c_info;
   237		data.info_size = ARRAY_SIZE(cp500_i2c_info);
   238	
   239		pdev = platform_device_register_resndata(&cp500->pci_dev->dev,
   240							 "i2c-keba", 0, res,
   241							 ARRAY_SIZE(res), &data,
   242							 sizeof(data));
   243		if (IS_ERR(pdev))
   244			return PTR_ERR(pdev);
   245		cp500->i2c = pdev;
   246	
   247		return 0;
   248	}
   249	
   250	static void cp500_register_platform_devs(struct cp500 *cp500)
   251	{
   252		struct device *dev = &cp500->pci_dev->dev;
   253	
   254		if (cp500_register_i2c(cp500))
   255			dev_warn(dev, "Failed to register i2c-keba!\n");
   256	}
   257	
   258	static void cp500_unregister_dev(struct platform_device **ppdev)
   259	{
   260		if (*ppdev) {
   261			platform_device_unregister(*ppdev);
 > 262			*ppdev = 0;
   263		}
   264	}
   265	

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

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

* Re: [PATCH 1/2] i2c: keba: Add KEBA I2C controller support
  2024-06-03 22:37   ` Andi Shyti
@ 2024-06-04 19:06     ` Gerhard Engleder
  0 siblings, 0 replies; 13+ messages in thread
From: Gerhard Engleder @ 2024-06-04 19:06 UTC (permalink / raw)
  To: Andi Shyti; +Cc: linux-i2c, arnd, gregkh, Gerhard Engleder

On 04.06.24 00:37, Andi Shyti wrote:
> Hi Gerhard,

Hello Andi

> On Sat, Jun 01, 2024 at 09:28:45PM +0200, Gerhard Engleder wrote:
>> From: Gerhard Engleder <eg@keba.com>
>>
>> The KEBA I2C controller is found in the system FPGA of KEBA PLC devices.
>> It is used to connect EEPROMs and hardware monitoring chips.
> 
> can you please add more information about the device, please?

I will add more information

>> +// SPDX-License-Identifier: GPL-2.0
>> +/*
>> + * Copyright (C) KEBA AG 2012
> 
> can we update the date here?

First driver version is from 2012. I will remove that line.

>> + * Copyright (C) KEBA Industrial Automation Gmbh 2024
>> + *
>> + * Driver for KEBA I2C controller FPGA IP core
>> + */
>> +
>> +#include <linux/module.h>
>> +#include <linux/platform_device.h>
>> +#include <linux/io.h>
>> +#include <linux/iopoll.h>
>> +#include <linux/i2c.h>
>> +#include <linux/platform_data/i2c-keba.h>
> 
> Can you sort them in alphabetical order, please?

Will be done.

>> +#define KI2C "i2c-keba"
>> +
>> +#define KI2C_CAPABILITY_REG	0x02
>> +#define KI2C_CONTROL_REG	0x04
>> +#define KI2C_CONTROL_DC_REG	0x05
>> +#define KI2C_STATUS_REG		0x08
>> +#define KI2C_STATUS_DC_REG	0x09
>> +#define KI2C_DATA_REG		0x0c
>> +
>> +#define KI2C_CAPABILITY_CRYPTO	0x01
> 
> This crypto is not used anywhere, did you add it for completness
> or have you forgotten to use it?

It is there for completeness/documentation.

>> +#define KI2C_CAPABILITY_DC	0x02
>> +
>> +#define KI2C_CONTROL_MEN	0x01
>> +#define KI2C_CONTROL_MSTA	0x02
>> +#define KI2C_CONTROL_RSTA	0x04
>> +#define KI2C_CONTROL_MTX	0x08
>> +#define KI2C_CONTROL_TXAK	0x10
>> +
>> +#define KI2C_STATUS_IN_USE	0x01
>> +#define KI2C_STATUS_ACK_CYC	0x02
>> +#define KI2C_STATUS_RXAK	0x04
>> +#define KI2C_STATUS_MCF		0x08
>> +
>> +#define KI2C_DC_SDA		0x01
>> +#define KI2C_DC_SCL		0x02
> 
> You could eventually make it as:
> 
> #define REG1_ADDR	0xXX
> #define   REG1_VAL_1	0xXX
> #define   REG1_VAL_2	0xXX
> #define   REG1_VAL_3	0xXX
> 
> #define REG2_ADDR	0xXX
> #define   REG2_VAL_1	0xXX
> #define   REG2_VAL_2	0xXX
> #define   REG2_VAL_3	0xXX
> 
> So that it's clear what belongs to what. Not a binding comment,
> just an aesthetic note.

I will give it a try.

>> +
>> +#define KI2C_INUSE_SLEEP_US	(2 * USEC_PER_MSEC)
>> +#define KI2C_INUSE_TIMEOUT_US	(10 * USEC_PER_SEC)
>> +
>> +#define KI2C_POLL_DELAY_US	5
>> +
>> +struct ki2c {
>> +	struct platform_device *pdev;
>> +	void __iomem *base;
>> +	struct i2c_adapter adapter;
>> +
>> +	struct i2c_client **client;
>> +	int client_size;
>> +};
>> +
>> +static int ki2c_inuse_lock(struct ki2c *ki2c)
>> +{
>> +	u8 sts;
>> +	int ret;
>> +
>> +	/* The I2C controller has an IN_USE bit for locking access to the
>> +	 * controller. This enables the use of I2C controller by other none
>> +	 * Linux processors.
> 
> Please use the proper commenting style:
> 
> 	/*
> 	 * Comment line 1
First driver version is from 2012. I will
> 	 * Comment line 2
> 	 * ...
> 	 * Comment line N
> 	 */
>

Sorry, I forgot that only net is using that style. Will be changed for
all comments.

>> +	 *
>> +	 * If the I2C controller is free, then the first read returns
>> +	 * IN_USE == 0. After that the I2C controller is locked and further
>> +	 * reads of IN_USE return 1.
>> +	 *
>> +	 * The I2C controller is unlocked by writing 1 into IN_USE.
>> +	 */
> 
> Basically this is a semaphore.

I will enhance the comment.

>> +	ret = readb_poll_timeout(ki2c->base + KI2C_STATUS_REG,
>> +				 sts, (sts & KI2C_STATUS_IN_USE) == 0,
>> +				 KI2C_INUSE_SLEEP_US, KI2C_INUSE_TIMEOUT_US);
> 
> we are waiting too long here... the documentaition recommends to
> use the readb_poll_timeout for less than 10us, while we are
> waiting 2ms.

I will check if it can be changed. Should be possible.

>> +	if (ret != 0)
>> +		dev_warn(&ki2c->pdev->dev, "%s err!\n", __func__);
>> +
>> +	return ret;
>> +}
>> +
>> +static void ki2c_inuse_unlock(struct ki2c *ki2c)
>> +{
>> +	/* unlock the controller by writing 1 into IN_USE */
>> +	iowrite8(KI2C_STATUS_IN_USE, ki2c->base + KI2C_STATUS_REG);
>> +}
>> +
>> +static int ki2c_wait_for_bit(u8 mask, void __iomem *addr, unsigned long timeout)
> 
> It looks more natural to have "addr" as a first argument.

I will reorder.

>> +{
>> +	u8 val;
>> +
>> +	return readb_poll_timeout(addr, val, (val & mask), KI2C_POLL_DELAY_US,
>> +				  jiffies_to_usecs(timeout));
>> +}
>> +static int ki2c_get_sda(struct ki2c *ki2c)
>> +{
>> +	/* capability KI2C_CAPABILITY_DC required */
>> +	return (ioread8(ki2c->base + KI2C_STATUS_DC_REG) & KI2C_DC_SDA) != 0;
> 
> Please avoid using such compact style.

Will make it more readable.

>> +}
>> +	/* generate clock cycles */
>> +	ki2c_set_scl(ki2c, val);
>> +	ndelay(KI2C_RECOVERY_NDELAY);
>> +	while (count++ < KI2C_RECOVERY_CLK_CNT * 2) {
>> +		if (val) {
>> +			/* SCL shouldn't be low here */
>> +			if (!ki2c_get_scl(ki2c)) {
>> +				dev_err(&ki2c->pdev->dev,
>> +					"SCL is stuck low!\n");
>> +				ret = -EBUSY;
>> +				break;
>> +			}
>> +
>> +			/* break if SDA is high */
>> +			if (ki2c_get_sda(ki2c))
>> +				break;
>> +		}
>> +
>> +		val = !val;
>> +		ki2c_set_scl(ki2c, val);
>> +		ndelay(KI2C_RECOVERY_NDELAY);
> 
> I don't know how much sense it makes to wait in ndelays, this is
> not going to be precise and... are we sure we want to wait
> atomically here?

So far there were no problems so it should be precise enough. Delay
is only 5us so sleeping is not necessary. This is done during startup,
sleeping would delay startup.

>> +	}
>> +
>> +	if (!ki2c_get_sda(ki2c)) {
>> +		dev_err(&ki2c->pdev->dev, "SDA is still low!\n");
> 
> To me this and the above dev_err's are just spamming the dmesg as
> we are already printing up in the probe function. If we want to
> have more precision printing, then we need to chose where the
> dev_err's need to be.

I will improve the error reporting.

>> +		ret = -EBUSY;
>> +	}
>> +
>> +	/* reenable controller */
>> +	iowrite8(KI2C_CONTROL_MEN, ki2c->base + KI2C_CONTROL_REG);
> 
> ...
> 
>> +	ret = ki2c_wait_for_data_ack(ki2c);
>> +	if (ret < 0)
>> +		/* For EEPROMs this is normal behavior during internal write
>> +		 * operation.
> 
> Please, mind the coding style.

I will do.

>> +		 */
>> +		dev_dbg(&ki2c->pdev->dev, "%s wait for ACK err at 0x%02x!\n",
>> +			__func__, m->addr);
>> +
>> +	return ret;
>> +}
> 
> ...
> 
>> +static int ki2c_probe(struct platform_device *pdev)
>> +{
>> +	struct i2c_keba_platform_data *pdata;
>> +	struct device *dev = &pdev->dev;
>> +	struct i2c_adapter *adap;
>> +	struct resource *io;
>> +	struct ki2c *ki2c;
>> +	int ret;
>> +
>> +	pdata = dev->platform_data;
>> +	if (pdata == 0) {
>> +		dev_err(dev, "Platform data not found!\n");
>> +		return -ENODEV;
> 
> please use dev_err_probe()

This function is new to me. I will check.


Thank you for your review!

Gerhard

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

end of thread, other threads:[~2024-06-04 20:02 UTC | newest]

Thread overview: 13+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2024-06-01 19:28 [PATCH 0/2] I2C controller support for KEBA PLCs Gerhard Engleder
2024-06-01 19:28 ` [PATCH 1/2] i2c: keba: Add KEBA I2C controller support Gerhard Engleder
2024-06-01 22:52   ` kernel test robot
2024-06-01 23:45   ` kernel test robot
2024-06-02 21:41   ` kernel test robot
2024-06-03 22:37   ` Andi Shyti
2024-06-04 19:06     ` Gerhard Engleder
2024-06-03 23:00   ` kernel test robot
2024-06-01 19:28 ` [PATCH 2/2] misc: keba: Add basic KEBA CP500 system FPGA support Gerhard Engleder
2024-06-02  7:19   ` Greg KH
2024-06-02 18:59     ` Gerhard Engleder
2024-06-02 23:37   ` kernel test robot
2024-06-04  5:13   ` kernel test robot

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).