linux-integrity.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH v10 0/5] Add Loongson Security Engine chip driver
@ 2025-05-28  6:59 Qunqin Zhao
  2025-05-28  6:59 ` [PATCH v10 1/5] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
                   ` (4 more replies)
  0 siblings, 5 replies; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  6:59 UTC (permalink / raw)
  To: lee, herbert, jarkko
  Cc: linux-kernel, loongarch, davem, linux-crypto, peterhuewe, jgg,
	linux-integrity, Qunqin Zhao

The Loongson Security Engine chip supports RNG, SM2, SM3 and SM4
accelerator engines. Each engine have its own DMA buffer provided
by the controller. The kernel cannot directly send commands to the
engine and must first send them to the controller, which will
forward them to the corresponding engine. Based on these engines,
TPM2 have been implemented in the chip, then let's treat TPM2 itself
as an engine.

v10: mfd: Cleanned up coding style.
     crypto: Unlimited tfm
     tpm: Added error check

v9: Moved the base driver back to drivers/mfd. Cleanned up coding style.

v8: Like Lee said, the base driver goes beyond MFD scope. Since these
    are all encryption related drivers and SM2, SM3, and SM4 drivers
    will be added to the crypto subsystem in the future, the base driver
    need to be changed when adding these drivers. Therefore, it may be
    more appropriate to place the base driver within the crypto
    subsystem.

    Removed complete callback in all driver. Removed the concepts of
    "channel", "msg" and "request" as they may be confusing. Used

v7: Addressed Huacai's comments.

v6: mfd :MFD_LS6000SE -> MFD_LOONGSON_SE,  ls6000se.c -> loongson-se.c

    crypto :CRYPTO_DEV_LS6000SE_RNG -> CRYPTO_DEV_LOONGSON_RNG,
    ls6000se-rng.c ->loongson-rng.c

    tpm: TCG_LSSE -> TCG_LOONGSON, tpm_lsse.c ->tpm_loongson.c

v5: Registered "ls6000se-rng" device in mfd driver


Qunqin Zhao (5):
  mfd: Add support for Loongson Security Engine chip controller
  crypto: loongson - add Loongson RNG driver support
  MAINTAINERS: Add entry for Loongson crypto driver
  tpm: Add a driver for Loongson TPM device
  MAINTAINERS: Add tpm_loongson.c to LOONGSON CRYPTO DRIVER entry

 MAINTAINERS                            |   9 +
 drivers/char/tpm/Kconfig               |   9 +
 drivers/char/tpm/Makefile              |   1 +
 drivers/char/tpm/tpm_loongson.c        |  84 ++++++++
 drivers/crypto/Kconfig                 |   1 +
 drivers/crypto/Makefile                |   1 +
 drivers/crypto/loongson/Kconfig        |   5 +
 drivers/crypto/loongson/Makefile       |   1 +
 drivers/crypto/loongson/loongson-rng.c | 211 +++++++++++++++++++++
 drivers/mfd/Kconfig                    |  11 ++
 drivers/mfd/Makefile                   |   2 +
 drivers/mfd/loongson-se.c              | 253 +++++++++++++++++++++++++
 include/linux/mfd/loongson-se.h        |  53 ++++++
 13 files changed, 641 insertions(+)
 create mode 100644 drivers/char/tpm/tpm_loongson.c
 create mode 100644 drivers/crypto/loongson/Kconfig
 create mode 100644 drivers/crypto/loongson/Makefile
 create mode 100644 drivers/crypto/loongson/loongson-rng.c
 create mode 100644 drivers/mfd/loongson-se.c
 create mode 100644 include/linux/mfd/loongson-se.h


base-commit: c89756bcf406af313d191cfe3709e7c175c5b0cd
-- 
2.45.2


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

* [PATCH v10 1/5] mfd: Add support for Loongson Security Engine chip controller
  2025-05-28  6:59 [PATCH v10 0/5] Add Loongson Security Engine chip driver Qunqin Zhao
@ 2025-05-28  6:59 ` Qunqin Zhao
  2025-05-28  6:59 ` [PATCH v10 2/5] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
                   ` (3 subsequent siblings)
  4 siblings, 0 replies; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  6:59 UTC (permalink / raw)
  To: lee, herbert, jarkko
  Cc: linux-kernel, loongarch, davem, linux-crypto, peterhuewe, jgg,
	linux-integrity, Qunqin Zhao, Yinggang Gu, Huacai Chen

Loongson Security Engine chip supports RNG, SM2, SM3 and SM4 accelerator
engines. This is the base driver for other specific engine drivers.

Co-developed-by: Yinggang Gu <guyinggang@loongson.cn>
Signed-off-by: Yinggang Gu <guyinggang@loongson.cn>
Signed-off-by: Qunqin Zhao <zhaoqunqin@loongson.cn>
Reviewed-by: Huacai Chen <chenhuacai@loongson.cn>
---
v10: Cleanned up coding style.

v8: As explained in the cover letter, moved this driver form MFD to here.
    Cleanned up coding style. Added some comments. Divided DMA memory
    equally among all engines.
 
v7: Moved Kconfig entry between MFD_INTEL_M10_BMC_PMCI and MFD_QNAP_MCU.
 
    Renamed se_enable_int_locked() to se_enable_int(), then moved the
    lock out of se_disable_int().

    "se_send_genl_cmd" ---> "se_send_cmd".
    "struct lsse_ch" ---> "struct se_channel".

v6: Replace all "ls6000se" with "loongson"
v5: Registered "ls6000se-rng" device.
v3-v4: None

 drivers/mfd/Kconfig             |  11 ++
 drivers/mfd/Makefile            |   2 +
 drivers/mfd/loongson-se.c       | 253 ++++++++++++++++++++++++++++++++
 include/linux/mfd/loongson-se.h |  53 +++++++
 4 files changed, 319 insertions(+)
 create mode 100644 drivers/mfd/loongson-se.c
 create mode 100644 include/linux/mfd/loongson-se.h

diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
index 96992af22..e121ae433 100644
--- a/drivers/mfd/Kconfig
+++ b/drivers/mfd/Kconfig
@@ -2389,6 +2389,17 @@ config MFD_INTEL_M10_BMC_PMCI
 	  additional drivers must be enabled in order to use the functionality
 	  of the device.
 
+config MFD_LOONGSON_SE
+	tristate "Loongson Security Engine chip controller driver"
+	depends on LOONGARCH && ACPI
+	select MFD_CORE
+	help
+	  The Loongson Security Engine chip supports RNG, SM2, SM3 and
+	  SM4 accelerator engines. Each engine have its own DMA buffer
+	  provided by the controller. The kernel cannot directly send
+	  commands to the engine and must first send them to the controller,
+	  which will forward them to the corresponding engine.
+
 config MFD_QNAP_MCU
 	tristate "QNAP microcontroller unit core driver"
 	depends on SERIAL_DEV_BUS
diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
index 5e5cc279a..1d63b38d1 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -291,3 +291,5 @@ obj-$(CONFIG_MFD_RSMU_I2C)	+= rsmu_i2c.o rsmu_core.o
 obj-$(CONFIG_MFD_RSMU_SPI)	+= rsmu_spi.o rsmu_core.o
 
 obj-$(CONFIG_MFD_UPBOARD_FPGA)	+= upboard-fpga.o
+
+obj-$(CONFIG_MFD_LOONGSON_SE)	+= loongson-se.o
diff --git a/drivers/mfd/loongson-se.c b/drivers/mfd/loongson-se.c
new file mode 100644
index 000000000..8aa71dcae
--- /dev/null
+++ b/drivers/mfd/loongson-se.c
@@ -0,0 +1,253 @@
+// SPDX-License-Identifier: GPL-2.0+
+/*
+ * Copyright (C) 2025 Loongson Technology Corporation Limited
+ *
+ * Author: Yinggang Gu <guyinggang@loongson.cn>
+ * Author: Qunqin Zhao <zhaoqunqin@loongson.cn>
+ */
+
+#include <linux/acpi.h>
+#include <linux/delay.h>
+#include <linux/device.h>
+#include <linux/dma-mapping.h>
+#include <linux/errno.h>
+#include <linux/init.h>
+#include <linux/interrupt.h>
+#include <linux/iopoll.h>
+#include <linux/kernel.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/loongson-se.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+
+struct loongson_se {
+	void __iomem *base;
+	spinlock_t dev_lock;
+	struct completion cmd_completion;
+
+	void *dmam_base;
+	int dmam_size;
+
+	struct mutex engine_init_lock;
+	struct loongson_se_engine engines[SE_ENGINE_MAX];
+};
+
+struct loongson_se_controller_cmd {
+	u32 command_id;
+	u32 info[7];
+};
+
+static int loongson_se_poll(struct loongson_se *se, u32 int_bit)
+{
+	u32 status;
+	int err;
+
+	spin_lock_irq(&se->dev_lock);
+
+	/* Notify the controller that the engine needs to be started */
+	writel(int_bit, se->base + SE_L2SINT_SET);
+
+	/* Polling until the controller has forwarded the engine command */
+	err = readl_relaxed_poll_timeout_atomic(se->base + SE_L2SINT_STAT, status,
+						!(status & int_bit),
+						1, LOONGSON_ENGINE_CMD_TIMEOUT_US);
+
+	spin_unlock_irq(&se->dev_lock);
+
+	return err;
+}
+
+static int loongson_se_send_controller_cmd(struct loongson_se *se,
+					   struct loongson_se_controller_cmd *cmd)
+{
+	u32 *send_cmd = (u32 *)cmd;
+	int err, i;
+
+	for (i = 0; i < SE_SEND_CMD_REG_LEN; i++)
+		writel(send_cmd[i], se->base + SE_SEND_CMD_REG + i * 4);
+
+	err = loongson_se_poll(se, SE_INT_CONTROLLER);
+	if (err)
+		return err;
+
+	return wait_for_completion_interruptible(&se->cmd_completion);
+}
+
+int loongson_se_send_engine_cmd(struct loongson_se_engine *engine)
+{
+	/*
+	 * After engine initialization, the controller already knows
+	 * where to obtain engine commands from. Now all we need to
+	 * do is notify the controller that the engine needs to be started.
+	 */
+	int err = loongson_se_poll(engine->se, BIT(engine->id));
+
+	if (err)
+		return err;
+
+	return wait_for_completion_interruptible(&engine->completion);
+}
+EXPORT_SYMBOL_GPL(loongson_se_send_engine_cmd);
+
+struct loongson_se_engine *loongson_se_init_engine(struct device *dev, int id)
+{
+	struct loongson_se *se = dev_get_drvdata(dev);
+	struct loongson_se_engine *engine = &se->engines[id];
+	struct loongson_se_controller_cmd cmd;
+
+	engine->se = se;
+	engine->id = id;
+	init_completion(&engine->completion);
+
+	/* Divide DMA memory equally among all engines */
+	engine->buffer_size = se->dmam_size / SE_ENGINE_MAX;
+	engine->buffer_off = (se->dmam_size / SE_ENGINE_MAX) * id;
+	engine->data_buffer = se->dmam_base + engine->buffer_off;
+
+	/*
+	 * There has no engine0, use its data buffer as command buffer for other
+	 * engines. The DMA memory size is obtained from the ACPI table, which
+	 * ensures that the data buffer size of engine0 is larger than the
+	 * command buffer size of all engines.
+	 */
+	engine->command = se->dmam_base + id * (2 * SE_ENGINE_CMD_SIZE);
+	engine->command_ret = engine->command + SE_ENGINE_CMD_SIZE;
+
+	mutex_lock(&se->engine_init_lock);
+
+	/* Tell the controller where to find engine command */
+	cmd.command_id = SE_CMD_SET_ENGINE_CMDBUF;
+	cmd.info[0] = id;
+	cmd.info[1] = engine->command - se->dmam_base;
+	cmd.info[2] = 2 * SE_ENGINE_CMD_SIZE;
+
+	if (loongson_se_send_controller_cmd(se, &cmd))
+		engine = NULL;
+
+	mutex_unlock(&se->engine_init_lock);
+
+	return engine;
+}
+EXPORT_SYMBOL_GPL(loongson_se_init_engine);
+
+static irqreturn_t se_irq_handler(int irq, void *dev_id)
+{
+	struct loongson_se *se = dev_id;
+	u32 int_status;
+	int id;
+
+	spin_lock(&se->dev_lock);
+
+	int_status = readl(se->base + SE_S2LINT_STAT);
+
+	/* For controller */
+	if (int_status & SE_INT_CONTROLLER) {
+		complete(&se->cmd_completion);
+		int_status &= ~SE_INT_CONTROLLER;
+		writel(SE_INT_CONTROLLER, se->base + SE_S2LINT_CL);
+	}
+
+	/* For engines */
+	while (int_status) {
+		id = __ffs(int_status);
+		complete(&se->engines[id].completion);
+		int_status &= ~BIT(id);
+		writel(BIT(id), se->base + SE_S2LINT_CL);
+	}
+
+	spin_unlock(&se->dev_lock);
+
+	return IRQ_HANDLED;
+}
+
+static int loongson_se_init(struct loongson_se *se, dma_addr_t addr, int size)
+{
+	struct loongson_se_controller_cmd cmd;
+	int err;
+
+	cmd.command_id = SE_CMD_START;
+	err = loongson_se_send_controller_cmd(se, &cmd);
+	if (err)
+		return err;
+
+	cmd.command_id = SE_CMD_SET_DMA;
+	cmd.info[0] = lower_32_bits(addr);
+	cmd.info[1] = upper_32_bits(addr);
+	cmd.info[2] = size;
+
+	return loongson_se_send_controller_cmd(se, &cmd);
+}
+
+static const struct mfd_cell engines[] = {
+	{ .name = "loongson-rng" },
+	{ .name = "loongson-tpm" },
+};
+
+static int loongson_se_probe(struct platform_device *pdev)
+{
+	struct device *dev = &pdev->dev;
+	struct loongson_se *se;
+	int nr_irq, irq, err, i;
+	dma_addr_t paddr;
+
+	se = devm_kmalloc(dev, sizeof(*se), GFP_KERNEL);
+	if (!se)
+		return -ENOMEM;
+
+	dev_set_drvdata(dev, se);
+	init_completion(&se->cmd_completion);
+	spin_lock_init(&se->dev_lock);
+	mutex_init(&se->engine_init_lock);
+
+	dma_set_mask_and_coherent(dev, DMA_BIT_MASK(64));
+	if (device_property_read_u32(dev, "dmam_size", &se->dmam_size))
+		return -ENODEV;
+
+	se->dmam_base = dmam_alloc_coherent(dev, se->dmam_size, &paddr, GFP_KERNEL);
+	if (!se->dmam_base)
+		return -ENOMEM;
+
+	se->base = devm_platform_ioremap_resource(pdev, 0);
+	if (IS_ERR(se->base))
+		return PTR_ERR(se->base);
+
+	writel(SE_INT_ALL, se->base + SE_S2LINT_EN);
+
+	nr_irq = platform_irq_count(pdev);
+	if (nr_irq <= 0)
+		return -ENODEV;
+
+	for (i = 0; i < nr_irq; i++) {
+		irq = platform_get_irq(pdev, i);
+		err = devm_request_irq(dev, irq, se_irq_handler, 0, "loongson-se", se);
+		if (err)
+			dev_err(dev, "failed to request IRQ: %d\n", irq);
+	}
+
+	err = loongson_se_init(se, paddr, se->dmam_size);
+	if (err)
+		return err;
+
+	return devm_mfd_add_devices(dev, PLATFORM_DEVID_NONE, engines,
+				    ARRAY_SIZE(engines), NULL, 0, NULL);
+}
+
+static const struct acpi_device_id loongson_se_acpi_match[] = {
+	{ "LOON0011", 0 },
+	{ }
+};
+MODULE_DEVICE_TABLE(acpi, loongson_se_acpi_match);
+
+static struct platform_driver loongson_se_driver = {
+	.probe   = loongson_se_probe,
+	.driver  = {
+		.name  = "loongson-se",
+		.acpi_match_table = loongson_se_acpi_match,
+	},
+};
+module_platform_driver(loongson_se_driver);
+
+MODULE_LICENSE("GPL");
+MODULE_AUTHOR("Yinggang Gu <guyinggang@loongson.cn>");
+MODULE_AUTHOR("Qunqin Zhao <zhaoqunqin@loongson.cn>");
+MODULE_DESCRIPTION("Loongson Security Engine chip controller driver");
diff --git a/include/linux/mfd/loongson-se.h b/include/linux/mfd/loongson-se.h
new file mode 100644
index 000000000..07afa0c25
--- /dev/null
+++ b/include/linux/mfd/loongson-se.h
@@ -0,0 +1,53 @@
+/* SPDX-License-Identifier: GPL-2.0+ */
+/* Copyright (C) 2025 Loongson Technology Corporation Limited */
+
+#ifndef __MFD_LOONGSON_SE_H__
+#define __MFD_LOONGSON_SE_H__
+
+#define LOONGSON_ENGINE_CMD_TIMEOUT_US	10000
+#define SE_SEND_CMD_REG			0x0
+#define SE_SEND_CMD_REG_LEN		0x8
+/* Controller command ID */
+#define SE_CMD_START			0x0
+#define SE_CMD_SET_DMA			0x3
+#define SE_CMD_SET_ENGINE_CMDBUF	0x4
+
+#define SE_S2LINT_STAT			0x88
+#define SE_S2LINT_EN			0x8c
+#define SE_S2LINT_CL			0x94
+#define SE_L2SINT_STAT			0x98
+#define SE_L2SINT_SET			0xa0
+
+#define SE_INT_ALL			0xffffffff
+#define SE_INT_CONTROLLER		BIT(0)
+
+#define SE_ENGINE_MAX			16
+#define SE_ENGINE_RNG			1
+#define SE_CMD_RNG			0x100
+
+#define SE_ENGINE_TPM			5
+#define SE_CMD_TPM			0x500
+
+#define SE_ENGINE_CMD_SIZE		32
+
+struct loongson_se_engine {
+	struct loongson_se *se;
+	int id;
+
+	/* Command buffer */
+	void *command;
+	void *command_ret;
+
+	void *data_buffer;
+	uint buffer_size;
+	/* Data buffer offset to DMA base */
+	uint buffer_off;
+
+	struct completion completion;
+
+};
+
+struct loongson_se_engine *loongson_se_init_engine(struct device *dev, int id);
+int loongson_se_send_engine_cmd(struct loongson_se_engine *engine);
+
+#endif
-- 
2.45.2


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

* [PATCH v10 2/5] crypto: loongson - add Loongson RNG driver support
  2025-05-28  6:59 [PATCH v10 0/5] Add Loongson Security Engine chip driver Qunqin Zhao
  2025-05-28  6:59 ` [PATCH v10 1/5] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
@ 2025-05-28  6:59 ` Qunqin Zhao
  2025-06-11  9:23   ` Herbert Xu
  2025-05-28  6:59 ` [PATCH v10 3/5] MAINTAINERS: Add entry for Loongson crypto driver Qunqin Zhao
                   ` (2 subsequent siblings)
  4 siblings, 1 reply; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  6:59 UTC (permalink / raw)
  To: lee, herbert, jarkko
  Cc: linux-kernel, loongarch, davem, linux-crypto, peterhuewe, jgg,
	linux-integrity, Qunqin Zhao, Yinggang Gu, Huacai Chen

Loongson's Random Number Generator is found inside Loongson Security
Engine chip.

Co-developed-by: Yinggang Gu <guyinggang@loongson.cn>
Signed-off-by: Yinggang Gu <guyinggang@loongson.cn>
Signed-off-by: Qunqin Zhao <zhaoqunqin@loongson.cn>
Reviewed-by: Huacai Chen <chenhuacai@loongson.cn>
---
v10: In the init callback, select the device with the minimum users,
     now the init callback shoud always return sucess.

     Add mutext_lock/unlock in generate and seed callback.
     Cleanned up coding style.
    
v8: Added reseed callbak. "lsrng" --> "loongson_rng".
v7: Change the lsrng_ prefix to loongson_rng_
v6: Replace all "ls6000se" with "loongson"
v2-v5: None 

 drivers/crypto/Kconfig                 |   1 +
 drivers/crypto/Makefile                |   1 +
 drivers/crypto/loongson/Kconfig        |   5 +
 drivers/crypto/loongson/Makefile       |   1 +
 drivers/crypto/loongson/loongson-rng.c | 211 +++++++++++++++++++++++++
 5 files changed, 219 insertions(+)
 create mode 100644 drivers/crypto/loongson/Kconfig
 create mode 100644 drivers/crypto/loongson/Makefile
 create mode 100644 drivers/crypto/loongson/loongson-rng.c

diff --git a/drivers/crypto/Kconfig b/drivers/crypto/Kconfig
index 568636977..a13f2a6cd 100644
--- a/drivers/crypto/Kconfig
+++ b/drivers/crypto/Kconfig
@@ -826,6 +826,7 @@ config CRYPTO_DEV_CCREE
 	  If unsure say Y.
 
 source "drivers/crypto/hisilicon/Kconfig"
+source "drivers/crypto/loongson/Kconfig"
 
 source "drivers/crypto/amlogic/Kconfig"
 
diff --git a/drivers/crypto/Makefile b/drivers/crypto/Makefile
index 22eadcc8f..125b99b24 100644
--- a/drivers/crypto/Makefile
+++ b/drivers/crypto/Makefile
@@ -44,6 +44,7 @@ obj-y += inside-secure/
 obj-$(CONFIG_CRYPTO_DEV_ARTPEC6) += axis/
 obj-y += xilinx/
 obj-y += hisilicon/
+obj-y += loongson/
 obj-$(CONFIG_CRYPTO_DEV_AMLOGIC_GXL) += amlogic/
 obj-y += intel/
 obj-y += starfive/
diff --git a/drivers/crypto/loongson/Kconfig b/drivers/crypto/loongson/Kconfig
new file mode 100644
index 000000000..15475da8f
--- /dev/null
+++ b/drivers/crypto/loongson/Kconfig
@@ -0,0 +1,5 @@
+config CRYPTO_DEV_LOONGSON_RNG
+	tristate "Support for Loongson RNG Driver"
+	depends on MFD_LOONGSON_SE
+	help
+	  Support for Loongson RNG Driver.
diff --git a/drivers/crypto/loongson/Makefile b/drivers/crypto/loongson/Makefile
new file mode 100644
index 000000000..1ce5ec32b
--- /dev/null
+++ b/drivers/crypto/loongson/Makefile
@@ -0,0 +1 @@
+obj-$(CONFIG_CRYPTO_DEV_LOONGSON_RNG)  += loongson-rng.o
diff --git a/drivers/crypto/loongson/loongson-rng.c b/drivers/crypto/loongson/loongson-rng.c
new file mode 100644
index 000000000..5a06d698e
--- /dev/null
+++ b/drivers/crypto/loongson/loongson-rng.c
@@ -0,0 +1,211 @@
+// SPDX-License-Identifier: GPL-2.0
+/* Copyright (c) 2019 HiSilicon Limited. */
+/* Copyright (c) 2025 Loongson Technology Corporation Limited. */
+
+#include <linux/crypto.h>
+#include <linux/err.h>
+#include <linux/hw_random.h>
+#include <linux/io.h>
+#include <linux/iopoll.h>
+#include <linux/kernel.h>
+#include <linux/list.h>
+#include <linux/mfd/loongson-se.h>
+#include <linux/module.h>
+#include <linux/mutex.h>
+#include <linux/platform_device.h>
+#include <linux/random.h>
+#include <crypto/internal/rng.h>
+
+#define SE_SEED_SIZE 32
+
+struct loongson_rng_list {
+	struct mutex lock;
+	struct list_head list;
+	int is_init;
+};
+
+struct loongson_rng {
+	u32 used;
+	struct loongson_se_engine *engine;
+	struct list_head list;
+	struct mutex lock;
+};
+
+struct loongson_rng_ctx {
+	struct loongson_rng *rng;
+};
+
+struct loongson_rng_cmd {
+	u32 cmd_id;
+	union {
+		u32 len;
+		u32 ret;
+	} u;
+	u32 seed_off;
+	u32 out_off;
+	u32 pad[4];
+};
+
+static struct loongson_rng_list rng_devices;
+
+static int loongson_rng_generate(struct crypto_rng *tfm, const u8 *src,
+			  unsigned int slen, u8 *dstn, unsigned int dlen)
+{
+	struct loongson_rng_ctx *ctx = crypto_rng_ctx(tfm);
+	struct loongson_rng *rng = ctx->rng;
+	struct loongson_rng_cmd *cmd = rng->engine->command;
+	int err, len;
+
+	mutex_lock(&rng->lock);
+	cmd->seed_off = 0;
+	do {
+		len = min(dlen, rng->engine->buffer_size);
+		cmd = rng->engine->command;
+		cmd->u.len = len;
+		err = loongson_se_send_engine_cmd(rng->engine);
+		if (err)
+			break;
+
+		cmd = rng->engine->command_ret;
+		if (cmd->u.ret) {
+			err = -EIO;
+			break;
+		}
+
+		memcpy(dstn, rng->engine->data_buffer, len);
+		dlen -= len;
+		dstn += len;
+	} while (dlen > 0);
+	mutex_unlock(&rng->lock);
+
+	return err;
+}
+
+static int loongson_rng_init(struct crypto_tfm *tfm)
+{
+	struct loongson_rng_ctx *ctx = crypto_tfm_ctx(tfm);
+	struct loongson_rng *rng;
+	u32 min_used = U32_MAX;
+
+	mutex_lock(&rng_devices.lock);
+	list_for_each_entry(rng, &rng_devices.list, list) {
+		if (rng->used < min_used) {
+			ctx->rng = rng;
+			min_used = rng->used;
+		}
+	}
+	ctx->rng->used++;
+	mutex_unlock(&rng_devices.lock);
+
+	return 0;
+}
+
+static void loongson_rng_exit(struct crypto_tfm *tfm)
+{
+	struct loongson_rng_ctx *ctx = crypto_tfm_ctx(tfm);
+
+	mutex_lock(&rng_devices.lock);
+	ctx->rng->used--;
+	mutex_unlock(&rng_devices.lock);
+}
+
+static int loongson_rng_seed(struct crypto_rng *tfm, const u8 *seed,
+			     unsigned int slen)
+{
+	struct loongson_rng_ctx *ctx = crypto_rng_ctx(tfm);
+	struct loongson_rng *rng = ctx->rng;
+	struct loongson_rng_cmd *cmd;
+	int err;
+
+	if (slen < SE_SEED_SIZE)
+		return -EINVAL;
+
+	slen = min(slen, rng->engine->buffer_size);
+
+	mutex_lock(&rng->lock);
+	cmd = rng->engine->command;
+	cmd->u.len = slen;
+	cmd->seed_off = rng->engine->buffer_off;
+	memcpy(rng->engine->data_buffer, seed, slen);
+	err = loongson_se_send_engine_cmd(rng->engine);
+	if (err)
+		goto out;
+
+	cmd = rng->engine->command_ret;
+	if (cmd->u.ret)
+		err = -EIO;
+out:
+	mutex_unlock(&rng->lock);
+
+	return err;
+}
+
+static struct rng_alg loongson_rng_alg = {
+	.generate = loongson_rng_generate,
+	.seed =	loongson_rng_seed,
+	.seedsize = SE_SEED_SIZE,
+	.base = {
+		.cra_name = "stdrng",
+		.cra_driver_name = "loongson_stdrng",
+		.cra_priority = 300,
+		.cra_ctxsize = sizeof(struct loongson_rng_ctx),
+		.cra_module = THIS_MODULE,
+		.cra_init = loongson_rng_init,
+		.cra_exit = loongson_rng_exit,
+	},
+};
+
+static void loongson_rng_add_to_list(struct loongson_rng *rng)
+{
+	mutex_lock(&rng_devices.lock);
+	list_add_tail(&rng->list, &rng_devices.list);
+	mutex_unlock(&rng_devices.lock);
+}
+
+static int loongson_rng_probe(struct platform_device *pdev)
+{
+	struct loongson_rng_cmd *cmd;
+	struct loongson_rng *rng;
+	int ret;
+
+	rng = devm_kzalloc(&pdev->dev, sizeof(*rng), GFP_KERNEL);
+	if (!rng)
+		return -ENOMEM;
+
+	rng->engine = loongson_se_init_engine(pdev->dev.parent, SE_ENGINE_RNG);
+	if (!rng->engine)
+		return -ENODEV;
+	cmd = rng->engine->command;
+	cmd->cmd_id = SE_CMD_RNG;
+	cmd->out_off = rng->engine->buffer_off;
+
+	if (!rng_devices.is_init) {
+		ret = crypto_register_rng(&loongson_rng_alg);
+		if (ret) {
+			dev_err(&pdev->dev, "failed to register crypto(%d)\n", ret);
+			return ret;
+		}
+		INIT_LIST_HEAD(&rng_devices.list);
+		mutex_init(&rng_devices.lock);
+		rng_devices.is_init = true;
+	}
+
+	mutex_init(&rng->lock);
+	loongson_rng_add_to_list(rng);
+
+	return 0;
+}
+
+static struct platform_driver loongson_rng_driver = {
+	.probe		= loongson_rng_probe,
+	.driver		= {
+		.name	= "loongson-rng",
+	},
+};
+module_platform_driver(loongson_rng_driver);
+
+MODULE_ALIAS("platform:loongson-rng");
+MODULE_LICENSE("GPL");
+MODULE_AUTHOR("Yinggang Gu <guyinggang@loongson.cn>");
+MODULE_AUTHOR("Qunqin Zhao <zhaoqunqin@loongson.cn>");
+MODULE_DESCRIPTION("Loongson Random Number Generator driver");
-- 
2.45.2


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

* [PATCH v10 3/5] MAINTAINERS: Add entry for Loongson crypto driver
  2025-05-28  6:59 [PATCH v10 0/5] Add Loongson Security Engine chip driver Qunqin Zhao
  2025-05-28  6:59 ` [PATCH v10 1/5] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
  2025-05-28  6:59 ` [PATCH v10 2/5] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
@ 2025-05-28  6:59 ` Qunqin Zhao
  2025-05-28  6:59 ` [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device Qunqin Zhao
  2025-05-28  7:17 ` [PATCH v10 0/5] Add Loongson Security Engine chip driver Huacai Chen
  4 siblings, 0 replies; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  6:59 UTC (permalink / raw)
  To: lee, herbert, jarkko
  Cc: linux-kernel, loongarch, davem, linux-crypto, peterhuewe, jgg,
	linux-integrity, Qunqin Zhao, Huacai Chen

This patch adds an entry for Loongson crypto driver in the list of
maintainers.

Signed-off-by: Qunqin Zhao <zhaoqunqin@loongson.cn>
Reviewed-by: Huacai Chen <chenhuacai@loongson.cn>
---
v10: None
v9: Added loongson-se.c/.h to the entry.
v8: "RNG" --> "crypto"
v7: Added Huacai's tag
v5-v6: None
v4: Changed tile to "Add entry for ...".
    Lowcased "Maintainers" in commit message.

 MAINTAINERS | 8 ++++++++
 1 file changed, 8 insertions(+)

diff --git a/MAINTAINERS b/MAINTAINERS
index 76926087e..0fd568a6b 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -13980,6 +13980,14 @@ S:	Maintained
 F:	Documentation/devicetree/bindings/pwm/loongson,ls7a-pwm.yaml
 F:	drivers/pwm/pwm-loongson.c
 
+LOONGSON CRYPTO DRIVER
+M:	Qunqin Zhao <zhaoqunqin@loongson.cn>
+L:	linux-crypto@vger.kernel.org
+S:	Maintained
+F:	drivers/crypto/loongson/
+F:	drivers/mfd/loongson-se.c
+F:	include/linux/mfd/loongson-se.h
+
 LOONGSON-2 SOC SERIES CLOCK DRIVER
 M:	Yinbo Zhu <zhuyinbo@loongson.cn>
 L:	linux-clk@vger.kernel.org
-- 
2.45.2


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

* [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  6:59 [PATCH v10 0/5] Add Loongson Security Engine chip driver Qunqin Zhao
                   ` (2 preceding siblings ...)
  2025-05-28  6:59 ` [PATCH v10 3/5] MAINTAINERS: Add entry for Loongson crypto driver Qunqin Zhao
@ 2025-05-28  6:59 ` Qunqin Zhao
  2025-05-28  7:57   ` Stefano Garzarella
  2025-05-28  7:17 ` [PATCH v10 0/5] Add Loongson Security Engine chip driver Huacai Chen
  4 siblings, 1 reply; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  6:59 UTC (permalink / raw)
  To: lee, herbert, jarkko
  Cc: linux-kernel, loongarch, davem, linux-crypto, peterhuewe, jgg,
	linux-integrity, Qunqin Zhao, Yinggang Gu, Huacai Chen

Loongson Security Engine supports random number generation, hash,
symmetric encryption and asymmetric encryption. Based on these
encryption functions, TPM2 have been implemented in the Loongson
Security Engine firmware. This driver is responsible for copying data
into the memory visible to the firmware and receiving data from the
firmware.

Co-developed-by: Yinggang Gu <guyinggang@loongson.cn>
Signed-off-by: Yinggang Gu <guyinggang@loongson.cn>
Signed-off-by: Qunqin Zhao <zhaoqunqin@loongson.cn>
Reviewed-by: Huacai Chen <chenhuacai@loongson.cn>
---
v10: Added error check in send and recv callbak
    
v9: "tpm_loongson_driver" --> "tpm_loongson"
    "depends on CRYPTO_DEV_LOONGSON_SE" --> "depends on MFD_LOONGSON_SE"

v8: In the send callback, it will wait until the TPM2 command is
    completed. So do not need to wait in the recv callback.
    Removed Jarkko's tag cause there are some changes in v8

v7: Moved Kconfig entry between TCG_IBMVTPM and TCG_XEN.
    Added Jarkko's tag(a little change, should be fine).
    
v6: Replace all "ls6000se" with "loongson"
    Prefix all with tpm_loongson instead of tpm_lsse.
    Removed Jarkko's tag cause there are some changes in v6

v5: None
v4: Prefix all with tpm_lsse instead of tpm.
    Removed MODULE_AUTHOR fields.

v3: Added reminder about Loongson security engine to git log.

 drivers/char/tpm/Kconfig        |  9 ++++
 drivers/char/tpm/Makefile       |  1 +
 drivers/char/tpm/tpm_loongson.c | 84 +++++++++++++++++++++++++++++++++
 3 files changed, 94 insertions(+)
 create mode 100644 drivers/char/tpm/tpm_loongson.c

diff --git a/drivers/char/tpm/Kconfig b/drivers/char/tpm/Kconfig
index dddd702b2..ba3924eb1 100644
--- a/drivers/char/tpm/Kconfig
+++ b/drivers/char/tpm/Kconfig
@@ -189,6 +189,15 @@ config TCG_IBMVTPM
 	  will be accessible from within Linux.  To compile this driver
 	  as a module, choose M here; the module will be called tpm_ibmvtpm.
 
+config TCG_LOONGSON
+	tristate "Loongson TPM Interface"
+	depends on MFD_LOONGSON_SE
+	help
+	  If you want to make Loongson TPM support available, say Yes and
+	  it will be accessible from within Linux. To compile this
+	  driver as a module, choose M here; the module will be called
+	  tpm_loongson.
+
 config TCG_XEN
 	tristate "XEN TPM Interface"
 	depends on TCG_TPM && XEN
diff --git a/drivers/char/tpm/Makefile b/drivers/char/tpm/Makefile
index 9de1b3ea3..5b5cdc0d3 100644
--- a/drivers/char/tpm/Makefile
+++ b/drivers/char/tpm/Makefile
@@ -46,3 +46,4 @@ obj-$(CONFIG_TCG_ARM_CRB_FFA) += tpm_crb_ffa.o
 obj-$(CONFIG_TCG_VTPM_PROXY) += tpm_vtpm_proxy.o
 obj-$(CONFIG_TCG_FTPM_TEE) += tpm_ftpm_tee.o
 obj-$(CONFIG_TCG_SVSM) += tpm_svsm.o
+obj-$(CONFIG_TCG_LOONGSON) += tpm_loongson.o
diff --git a/drivers/char/tpm/tpm_loongson.c b/drivers/char/tpm/tpm_loongson.c
new file mode 100644
index 000000000..5cbdb37f8
--- /dev/null
+++ b/drivers/char/tpm/tpm_loongson.c
@@ -0,0 +1,84 @@
+// SPDX-License-Identifier: GPL-2.0
+/* Copyright (c) 2025 Loongson Technology Corporation Limited. */
+
+#include <linux/device.h>
+#include <linux/mfd/loongson-se.h>
+#include <linux/platform_device.h>
+#include <linux/wait.h>
+
+#include "tpm.h"
+
+struct tpm_loongson_cmd {
+	u32 cmd_id;
+	u32 data_off;
+	u32 data_len;
+	u32 pad[5];
+};
+
+static int tpm_loongson_recv(struct tpm_chip *chip, u8 *buf, size_t count)
+{
+	struct loongson_se_engine *tpm_engine = dev_get_drvdata(&chip->dev);
+	struct tpm_loongson_cmd *cmd_ret = tpm_engine->command_ret;
+
+	if (cmd_ret->data_len > count)
+		return -EIO;
+
+	memcpy(buf, tpm_engine->data_buffer, cmd_ret->data_len);
+
+	return cmd_ret->data_len;
+}
+
+static int tpm_loongson_send(struct tpm_chip *chip, u8 *buf, size_t count)
+{
+	struct loongson_se_engine *tpm_engine = dev_get_drvdata(&chip->dev);
+	struct tpm_loongson_cmd *cmd = tpm_engine->command;
+
+	if (count > tpm_engine->buffer_size)
+		return -E2BIG;
+
+	cmd->data_len = count;
+	memcpy(tpm_engine->data_buffer, buf, count);
+
+	return loongson_se_send_engine_cmd(tpm_engine);
+}
+
+static const struct tpm_class_ops tpm_loongson_ops = {
+	.flags = TPM_OPS_AUTO_STARTUP,
+	.recv = tpm_loongson_recv,
+	.send = tpm_loongson_send,
+};
+
+static int tpm_loongson_probe(struct platform_device *pdev)
+{
+	struct loongson_se_engine *tpm_engine;
+	struct device *dev = &pdev->dev;
+	struct tpm_loongson_cmd *cmd;
+	struct tpm_chip *chip;
+
+	tpm_engine = loongson_se_init_engine(dev->parent, SE_ENGINE_TPM);
+	if (!tpm_engine)
+		return -ENODEV;
+	cmd = tpm_engine->command;
+	cmd->cmd_id = SE_CMD_TPM;
+	cmd->data_off = tpm_engine->buffer_off;
+
+	chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
+	if (IS_ERR(chip))
+		return PTR_ERR(chip);
+	chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
+	dev_set_drvdata(&chip->dev, tpm_engine);
+
+	return tpm_chip_register(chip);
+}
+
+static struct platform_driver tpm_loongson = {
+	.probe   = tpm_loongson_probe,
+	.driver  = {
+		.name  = "loongson-tpm",
+	},
+};
+module_platform_driver(tpm_loongson);
+
+MODULE_ALIAS("platform:loongson-tpm");
+MODULE_LICENSE("GPL");
+MODULE_DESCRIPTION("Loongson TPM driver");
-- 
2.45.2


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

* Re: [PATCH v10 0/5] Add Loongson Security Engine chip driver
  2025-05-28  6:59 [PATCH v10 0/5] Add Loongson Security Engine chip driver Qunqin Zhao
                   ` (3 preceding siblings ...)
  2025-05-28  6:59 ` [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device Qunqin Zhao
@ 2025-05-28  7:17 ` Huacai Chen
  2025-05-28  7:42   ` Yanteng Si
  2025-05-28  8:05   ` Qunqin Zhao
  4 siblings, 2 replies; 21+ messages in thread
From: Huacai Chen @ 2025-05-28  7:17 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity

Hi, Qunqin,

As I said before, why the patch "MAINTAINERS: Add entry for Loongson
Security Module driver" is missing?

Huacai

On Wed, May 28, 2025 at 2:59 PM Qunqin Zhao <zhaoqunqin@loongson.cn> wrote:
>
> The Loongson Security Engine chip supports RNG, SM2, SM3 and SM4
> accelerator engines. Each engine have its own DMA buffer provided
> by the controller. The kernel cannot directly send commands to the
> engine and must first send them to the controller, which will
> forward them to the corresponding engine. Based on these engines,
> TPM2 have been implemented in the chip, then let's treat TPM2 itself
> as an engine.
>
> v10: mfd: Cleanned up coding style.
>      crypto: Unlimited tfm
>      tpm: Added error check
>
> v9: Moved the base driver back to drivers/mfd. Cleanned up coding style.
>
> v8: Like Lee said, the base driver goes beyond MFD scope. Since these
>     are all encryption related drivers and SM2, SM3, and SM4 drivers
>     will be added to the crypto subsystem in the future, the base driver
>     need to be changed when adding these drivers. Therefore, it may be
>     more appropriate to place the base driver within the crypto
>     subsystem.
>
>     Removed complete callback in all driver. Removed the concepts of
>     "channel", "msg" and "request" as they may be confusing. Used
>
> v7: Addressed Huacai's comments.
>
> v6: mfd :MFD_LS6000SE -> MFD_LOONGSON_SE,  ls6000se.c -> loongson-se.c
>
>     crypto :CRYPTO_DEV_LS6000SE_RNG -> CRYPTO_DEV_LOONGSON_RNG,
>     ls6000se-rng.c ->loongson-rng.c
>
>     tpm: TCG_LSSE -> TCG_LOONGSON, tpm_lsse.c ->tpm_loongson.c
>
> v5: Registered "ls6000se-rng" device in mfd driver
>
>
> Qunqin Zhao (5):
>   mfd: Add support for Loongson Security Engine chip controller
>   crypto: loongson - add Loongson RNG driver support
>   MAINTAINERS: Add entry for Loongson crypto driver
>   tpm: Add a driver for Loongson TPM device
>   MAINTAINERS: Add tpm_loongson.c to LOONGSON CRYPTO DRIVER entry
>
>  MAINTAINERS                            |   9 +
>  drivers/char/tpm/Kconfig               |   9 +
>  drivers/char/tpm/Makefile              |   1 +
>  drivers/char/tpm/tpm_loongson.c        |  84 ++++++++
>  drivers/crypto/Kconfig                 |   1 +
>  drivers/crypto/Makefile                |   1 +
>  drivers/crypto/loongson/Kconfig        |   5 +
>  drivers/crypto/loongson/Makefile       |   1 +
>  drivers/crypto/loongson/loongson-rng.c | 211 +++++++++++++++++++++
>  drivers/mfd/Kconfig                    |  11 ++
>  drivers/mfd/Makefile                   |   2 +
>  drivers/mfd/loongson-se.c              | 253 +++++++++++++++++++++++++
>  include/linux/mfd/loongson-se.h        |  53 ++++++
>  13 files changed, 641 insertions(+)
>  create mode 100644 drivers/char/tpm/tpm_loongson.c
>  create mode 100644 drivers/crypto/loongson/Kconfig
>  create mode 100644 drivers/crypto/loongson/Makefile
>  create mode 100644 drivers/crypto/loongson/loongson-rng.c
>  create mode 100644 drivers/mfd/loongson-se.c
>  create mode 100644 include/linux/mfd/loongson-se.h
>
>
> base-commit: c89756bcf406af313d191cfe3709e7c175c5b0cd
> --
> 2.45.2
>
>

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

* Re: [PATCH v10 0/5] Add Loongson Security Engine chip driver
  2025-05-28  7:17 ` [PATCH v10 0/5] Add Loongson Security Engine chip driver Huacai Chen
@ 2025-05-28  7:42   ` Yanteng Si
  2025-05-28  8:05   ` Qunqin Zhao
  1 sibling, 0 replies; 21+ messages in thread
From: Yanteng Si @ 2025-05-28  7:42 UTC (permalink / raw)
  To: Huacai Chen, Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity

在 5/28/25 3:17 PM, Huacai Chen 写道:
> Hi, Qunqin,
> 
> As I said before, why the patch "MAINTAINERS: Add entry for Loongson
> Security Module driver" is missing?

Similar issues widely exist in the Loongarch mailing list.
The cause should be attributed to the mail server of Loongson.

It seems that Loongson Mail can only send no more than five
emails at a time. I suggest abandoning the use of Loongson Mail.


Thanks,
Yanteng

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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  6:59 ` [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device Qunqin Zhao
@ 2025-05-28  7:57   ` Stefano Garzarella
  2025-05-28  8:42     ` Qunqin Zhao
  0 siblings, 1 reply; 21+ messages in thread
From: Stefano Garzarella @ 2025-05-28  7:57 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen

On Wed, May 28, 2025 at 02:59:43PM +0800, Qunqin Zhao wrote:
>Loongson Security Engine supports random number generation, hash,
>symmetric encryption and asymmetric encryption. Based on these
>encryption functions, TPM2 have been implemented in the Loongson
>Security Engine firmware. This driver is responsible for copying data
>into the memory visible to the firmware and receiving data from the
>firmware.
>
>Co-developed-by: Yinggang Gu <guyinggang@loongson.cn>
>Signed-off-by: Yinggang Gu <guyinggang@loongson.cn>
>Signed-off-by: Qunqin Zhao <zhaoqunqin@loongson.cn>
>Reviewed-by: Huacai Chen <chenhuacai@loongson.cn>
>---
>v10: Added error check in send and recv callbak
>
>v9: "tpm_loongson_driver" --> "tpm_loongson"
>    "depends on CRYPTO_DEV_LOONGSON_SE" --> "depends on MFD_LOONGSON_SE"
>
>v8: In the send callback, it will wait until the TPM2 command is
>    completed. So do not need to wait in the recv callback.
>    Removed Jarkko's tag cause there are some changes in v8
>
>v7: Moved Kconfig entry between TCG_IBMVTPM and TCG_XEN.
>    Added Jarkko's tag(a little change, should be fine).
>
>v6: Replace all "ls6000se" with "loongson"
>    Prefix all with tpm_loongson instead of tpm_lsse.
>    Removed Jarkko's tag cause there are some changes in v6
>
>v5: None
>v4: Prefix all with tpm_lsse instead of tpm.
>    Removed MODULE_AUTHOR fields.
>
>v3: Added reminder about Loongson security engine to git log.
>
> drivers/char/tpm/Kconfig        |  9 ++++
> drivers/char/tpm/Makefile       |  1 +
> drivers/char/tpm/tpm_loongson.c | 84 +++++++++++++++++++++++++++++++++
> 3 files changed, 94 insertions(+)
> create mode 100644 drivers/char/tpm/tpm_loongson.c
>
>diff --git a/drivers/char/tpm/Kconfig b/drivers/char/tpm/Kconfig
>index dddd702b2..ba3924eb1 100644
>--- a/drivers/char/tpm/Kconfig
>+++ b/drivers/char/tpm/Kconfig
>@@ -189,6 +189,15 @@ config TCG_IBMVTPM
> 	  will be accessible from within Linux.  To compile this driver
> 	  as a module, choose M here; the module will be called tpm_ibmvtpm.
>
>+config TCG_LOONGSON
>+	tristate "Loongson TPM Interface"
>+	depends on MFD_LOONGSON_SE
>+	help
>+	  If you want to make Loongson TPM support available, say Yes and
>+	  it will be accessible from within Linux. To compile this
>+	  driver as a module, choose M here; the module will be called
>+	  tpm_loongson.
>+
> config TCG_XEN
> 	tristate "XEN TPM Interface"
> 	depends on TCG_TPM && XEN
>diff --git a/drivers/char/tpm/Makefile b/drivers/char/tpm/Makefile
>index 9de1b3ea3..5b5cdc0d3 100644
>--- a/drivers/char/tpm/Makefile
>+++ b/drivers/char/tpm/Makefile
>@@ -46,3 +46,4 @@ obj-$(CONFIG_TCG_ARM_CRB_FFA) += tpm_crb_ffa.o
> obj-$(CONFIG_TCG_VTPM_PROXY) += tpm_vtpm_proxy.o
> obj-$(CONFIG_TCG_FTPM_TEE) += tpm_ftpm_tee.o
> obj-$(CONFIG_TCG_SVSM) += tpm_svsm.o
>+obj-$(CONFIG_TCG_LOONGSON) += tpm_loongson.o
>diff --git a/drivers/char/tpm/tpm_loongson.c b/drivers/char/tpm/tpm_loongson.c
>new file mode 100644
>index 000000000..5cbdb37f8
>--- /dev/null
>+++ b/drivers/char/tpm/tpm_loongson.c
>@@ -0,0 +1,84 @@
>+// SPDX-License-Identifier: GPL-2.0
>+/* Copyright (c) 2025 Loongson Technology Corporation Limited. */
>+
>+#include <linux/device.h>
>+#include <linux/mfd/loongson-se.h>
>+#include <linux/platform_device.h>
>+#include <linux/wait.h>
>+
>+#include "tpm.h"
>+
>+struct tpm_loongson_cmd {
>+	u32 cmd_id;
>+	u32 data_off;
>+	u32 data_len;
>+	u32 pad[5];
>+};
>+
>+static int tpm_loongson_recv(struct tpm_chip *chip, u8 *buf, size_t count)
>+{
>+	struct loongson_se_engine *tpm_engine = dev_get_drvdata(&chip->dev);
>+	struct tpm_loongson_cmd *cmd_ret = tpm_engine->command_ret;
>+
>+	if (cmd_ret->data_len > count)
>+		return -EIO;
>+
>+	memcpy(buf, tpm_engine->data_buffer, cmd_ret->data_len);
>+
>+	return cmd_ret->data_len;
>+}
>+
>+static int tpm_loongson_send(struct tpm_chip *chip, u8 *buf, size_t count)
>+{
>+	struct loongson_se_engine *tpm_engine = dev_get_drvdata(&chip->dev);
>+	struct tpm_loongson_cmd *cmd = tpm_engine->command;
>+
>+	if (count > tpm_engine->buffer_size)
>+		return -E2BIG;
>+
>+	cmd->data_len = count;
>+	memcpy(tpm_engine->data_buffer, buf, count);
>+
>+	return loongson_se_send_engine_cmd(tpm_engine);
>+}
>+
>+static const struct tpm_class_ops tpm_loongson_ops = {
>+	.flags = TPM_OPS_AUTO_STARTUP,
>+	.recv = tpm_loongson_recv,
>+	.send = tpm_loongson_send,
>+};
>+
>+static int tpm_loongson_probe(struct platform_device *pdev)
>+{
>+	struct loongson_se_engine *tpm_engine;
>+	struct device *dev = &pdev->dev;
>+	struct tpm_loongson_cmd *cmd;
>+	struct tpm_chip *chip;
>+
>+	tpm_engine = loongson_se_init_engine(dev->parent, SE_ENGINE_TPM);
>+	if (!tpm_engine)
>+		return -ENODEV;
>+	cmd = tpm_engine->command;
>+	cmd->cmd_id = SE_CMD_TPM;
>+	cmd->data_off = tpm_engine->buffer_off;
>+
>+	chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
>+	if (IS_ERR(chip))
>+		return PTR_ERR(chip);
>+	chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;

Why setting TPM_CHIP_FLAG_IRQ?

IIUC this driver is similar to ftpm and svsm where the send is 
synchronous so having .status, .cancel, etc. set to 0 should be enough 
to call .recv() just after send() in tpm_try_transmit(). See commit 
980a573621ea ("tpm: Make chip->{status,cancel,req_canceled} opt")

BTW, I think I should touch also this driver in the next version of my 
series that I'll send after the merge window:
https://lore.kernel.org/linux-integrity/20250514134630.137621-1-sgarzare@redhat.com/

The rest LGTM!

Thanks,
Stefano

>+	dev_set_drvdata(&chip->dev, tpm_engine);
>+
>+	return tpm_chip_register(chip);
>+}
>+
>+static struct platform_driver tpm_loongson = {
>+	.probe   = tpm_loongson_probe,
>+	.driver  = {
>+		.name  = "loongson-tpm",
>+	},
>+};
>+module_platform_driver(tpm_loongson);
>+
>+MODULE_ALIAS("platform:loongson-tpm");
>+MODULE_LICENSE("GPL");
>+MODULE_DESCRIPTION("Loongson TPM driver");
>-- 
>2.45.2
>
>


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

* Re: [PATCH v10 0/5] Add Loongson Security Engine chip driver
  2025-05-28  7:17 ` [PATCH v10 0/5] Add Loongson Security Engine chip driver Huacai Chen
  2025-05-28  7:42   ` Yanteng Si
@ 2025-05-28  8:05   ` Qunqin Zhao
  2025-05-28  8:17     ` Huacai Chen
  1 sibling, 1 reply; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  8:05 UTC (permalink / raw)
  To: Huacai Chen
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity


在 2025/5/28 下午3:17, Huacai Chen 写道:
> Hi, Qunqin,
>
> As I said before, why the patch "MAINTAINERS: Add entry for Loongson
> Security Module driver" is missing?

Hi, Huacai

https://lore.kernel.org/all/8e55801a-a46e-58d5-cf84-2ee8a733df9a@loongson.cn/

Thanks,

Qunqin.

>
> Huacai
>
> On Wed, May 28, 2025 at 2:59 PM Qunqin Zhao <zhaoqunqin@loongson.cn> wrote:
>> The Loongson Security Engine chip supports RNG, SM2, SM3 and SM4
>> accelerator engines. Each engine have its own DMA buffer provided
>> by the controller. The kernel cannot directly send commands to the
>> engine and must first send them to the controller, which will
>> forward them to the corresponding engine. Based on these engines,
>> TPM2 have been implemented in the chip, then let's treat TPM2 itself
>> as an engine.
>>
>> v10: mfd: Cleanned up coding style.
>>       crypto: Unlimited tfm
>>       tpm: Added error check
>>
>> v9: Moved the base driver back to drivers/mfd. Cleanned up coding style.
>>
>> v8: Like Lee said, the base driver goes beyond MFD scope. Since these
>>      are all encryption related drivers and SM2, SM3, and SM4 drivers
>>      will be added to the crypto subsystem in the future, the base driver
>>      need to be changed when adding these drivers. Therefore, it may be
>>      more appropriate to place the base driver within the crypto
>>      subsystem.
>>
>>      Removed complete callback in all driver. Removed the concepts of
>>      "channel", "msg" and "request" as they may be confusing. Used
>>
>> v7: Addressed Huacai's comments.
>>
>> v6: mfd :MFD_LS6000SE -> MFD_LOONGSON_SE,  ls6000se.c -> loongson-se.c
>>
>>      crypto :CRYPTO_DEV_LS6000SE_RNG -> CRYPTO_DEV_LOONGSON_RNG,
>>      ls6000se-rng.c ->loongson-rng.c
>>
>>      tpm: TCG_LSSE -> TCG_LOONGSON, tpm_lsse.c ->tpm_loongson.c
>>
>> v5: Registered "ls6000se-rng" device in mfd driver
>>
>>
>> Qunqin Zhao (5):
>>    mfd: Add support for Loongson Security Engine chip controller
>>    crypto: loongson - add Loongson RNG driver support
>>    MAINTAINERS: Add entry for Loongson crypto driver
>>    tpm: Add a driver for Loongson TPM device
>>    MAINTAINERS: Add tpm_loongson.c to LOONGSON CRYPTO DRIVER entry
>>
>>   MAINTAINERS                            |   9 +
>>   drivers/char/tpm/Kconfig               |   9 +
>>   drivers/char/tpm/Makefile              |   1 +
>>   drivers/char/tpm/tpm_loongson.c        |  84 ++++++++
>>   drivers/crypto/Kconfig                 |   1 +
>>   drivers/crypto/Makefile                |   1 +
>>   drivers/crypto/loongson/Kconfig        |   5 +
>>   drivers/crypto/loongson/Makefile       |   1 +
>>   drivers/crypto/loongson/loongson-rng.c | 211 +++++++++++++++++++++
>>   drivers/mfd/Kconfig                    |  11 ++
>>   drivers/mfd/Makefile                   |   2 +
>>   drivers/mfd/loongson-se.c              | 253 +++++++++++++++++++++++++
>>   include/linux/mfd/loongson-se.h        |  53 ++++++
>>   13 files changed, 641 insertions(+)
>>   create mode 100644 drivers/char/tpm/tpm_loongson.c
>>   create mode 100644 drivers/crypto/loongson/Kconfig
>>   create mode 100644 drivers/crypto/loongson/Makefile
>>   create mode 100644 drivers/crypto/loongson/loongson-rng.c
>>   create mode 100644 drivers/mfd/loongson-se.c
>>   create mode 100644 include/linux/mfd/loongson-se.h
>>
>>
>> base-commit: c89756bcf406af313d191cfe3709e7c175c5b0cd
>> --
>> 2.45.2
>>
>>


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

* Re: [PATCH v10 0/5] Add Loongson Security Engine chip driver
  2025-05-28  8:05   ` Qunqin Zhao
@ 2025-05-28  8:17     ` Huacai Chen
  2025-05-28  9:14       ` Yanteng Si
  0 siblings, 1 reply; 21+ messages in thread
From: Huacai Chen @ 2025-05-28  8:17 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity

On Wed, May 28, 2025 at 4:06 PM Qunqin Zhao <zhaoqunqin@loongson.cn> wrote:
>
>
> 在 2025/5/28 下午3:17, Huacai Chen 写道:
> > Hi, Qunqin,
> >
> > As I said before, why the patch "MAINTAINERS: Add entry for Loongson
> > Security Module driver" is missing?
>
> Hi, Huacai
>
> https://lore.kernel.org/all/8e55801a-a46e-58d5-cf84-2ee8a733df9a@loongson.cn/
Sorry, I missed this email. But if you put all files in one entry, you
can merge Patch-3 and Patch-5 as the last patch (then you will also
not meet the 5 patches limit).

Huacai

>
> Thanks,
>
> Qunqin.
>
> >
> > Huacai
> >
> > On Wed, May 28, 2025 at 2:59 PM Qunqin Zhao <zhaoqunqin@loongson.cn> wrote:
> >> The Loongson Security Engine chip supports RNG, SM2, SM3 and SM4
> >> accelerator engines. Each engine have its own DMA buffer provided
> >> by the controller. The kernel cannot directly send commands to the
> >> engine and must first send them to the controller, which will
> >> forward them to the corresponding engine. Based on these engines,
> >> TPM2 have been implemented in the chip, then let's treat TPM2 itself
> >> as an engine.
> >>
> >> v10: mfd: Cleanned up coding style.
> >>       crypto: Unlimited tfm
> >>       tpm: Added error check
> >>
> >> v9: Moved the base driver back to drivers/mfd. Cleanned up coding style.
> >>
> >> v8: Like Lee said, the base driver goes beyond MFD scope. Since these
> >>      are all encryption related drivers and SM2, SM3, and SM4 drivers
> >>      will be added to the crypto subsystem in the future, the base driver
> >>      need to be changed when adding these drivers. Therefore, it may be
> >>      more appropriate to place the base driver within the crypto
> >>      subsystem.
> >>
> >>      Removed complete callback in all driver. Removed the concepts of
> >>      "channel", "msg" and "request" as they may be confusing. Used
> >>
> >> v7: Addressed Huacai's comments.
> >>
> >> v6: mfd :MFD_LS6000SE -> MFD_LOONGSON_SE,  ls6000se.c -> loongson-se.c
> >>
> >>      crypto :CRYPTO_DEV_LS6000SE_RNG -> CRYPTO_DEV_LOONGSON_RNG,
> >>      ls6000se-rng.c ->loongson-rng.c
> >>
> >>      tpm: TCG_LSSE -> TCG_LOONGSON, tpm_lsse.c ->tpm_loongson.c
> >>
> >> v5: Registered "ls6000se-rng" device in mfd driver
> >>
> >>
> >> Qunqin Zhao (5):
> >>    mfd: Add support for Loongson Security Engine chip controller
> >>    crypto: loongson - add Loongson RNG driver support
> >>    MAINTAINERS: Add entry for Loongson crypto driver
> >>    tpm: Add a driver for Loongson TPM device
> >>    MAINTAINERS: Add tpm_loongson.c to LOONGSON CRYPTO DRIVER entry
> >>
> >>   MAINTAINERS                            |   9 +
> >>   drivers/char/tpm/Kconfig               |   9 +
> >>   drivers/char/tpm/Makefile              |   1 +
> >>   drivers/char/tpm/tpm_loongson.c        |  84 ++++++++
> >>   drivers/crypto/Kconfig                 |   1 +
> >>   drivers/crypto/Makefile                |   1 +
> >>   drivers/crypto/loongson/Kconfig        |   5 +
> >>   drivers/crypto/loongson/Makefile       |   1 +
> >>   drivers/crypto/loongson/loongson-rng.c | 211 +++++++++++++++++++++
> >>   drivers/mfd/Kconfig                    |  11 ++
> >>   drivers/mfd/Makefile                   |   2 +
> >>   drivers/mfd/loongson-se.c              | 253 +++++++++++++++++++++++++
> >>   include/linux/mfd/loongson-se.h        |  53 ++++++
> >>   13 files changed, 641 insertions(+)
> >>   create mode 100644 drivers/char/tpm/tpm_loongson.c
> >>   create mode 100644 drivers/crypto/loongson/Kconfig
> >>   create mode 100644 drivers/crypto/loongson/Makefile
> >>   create mode 100644 drivers/crypto/loongson/loongson-rng.c
> >>   create mode 100644 drivers/mfd/loongson-se.c
> >>   create mode 100644 include/linux/mfd/loongson-se.h
> >>
> >>
> >> base-commit: c89756bcf406af313d191cfe3709e7c175c5b0cd
> >> --
> >> 2.45.2
> >>
> >>
>

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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  7:57   ` Stefano Garzarella
@ 2025-05-28  8:42     ` Qunqin Zhao
  2025-05-28  9:00       ` Stefano Garzarella
  0 siblings, 1 reply; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  8:42 UTC (permalink / raw)
  To: Stefano Garzarella
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen


在 2025/5/28 下午3:57, Stefano Garzarella 写道:
>> +    chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
>> +    if (IS_ERR(chip))
>> +        return PTR_ERR(chip);
>> +    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
>
> Why setting TPM_CHIP_FLAG_IRQ?

When tpm_engine completes  TPM_CC* command,

the hardware will indeed trigger an interrupt to the kernel.

>
> IIUC this driver is similar to ftpm and svsm where the send is 
> synchronous so having .status, .cancel, etc. set to 0 should be enough 
> to call .recv() just after send() in tpm_try_transmit(). See commit 
> 980a573621ea ("tpm: Make chip->{status,cancel,req_canceled} opt")
The send callback would wait until the TPM_CC* command complete. We 
don't need a poll.

Thanks,

Qunqin.

>
> BTW, I think I should touch also this driver in the next version of my 
> series that I'll send after the merge window:
> https://lore.kernel.org/linux-integrity/20250514134630.137621-1-sgarzare@redhat.com/ 
>
>
> The rest LGTM!
>
> Thanks,
> Stefano


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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  8:42     ` Qunqin Zhao
@ 2025-05-28  9:00       ` Stefano Garzarella
  2025-05-28  9:24         ` Qunqin Zhao
  0 siblings, 1 reply; 21+ messages in thread
From: Stefano Garzarella @ 2025-05-28  9:00 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen

On Wed, May 28, 2025 at 04:42:05PM +0800, Qunqin Zhao wrote:
>
>在 2025/5/28 下午3:57, Stefano Garzarella 写道:
>>>+    chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
>>>+    if (IS_ERR(chip))
>>>+        return PTR_ERR(chip);
>>>+    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
>>
>>Why setting TPM_CHIP_FLAG_IRQ?
>
>When tpm_engine completes  TPM_CC* command,
>
>the hardware will indeed trigger an interrupt to the kernel.

IIUC that is hidden by loongson_se_send_engine_cmd(), that for this 
driver is completely synchronous, no?

>
>>
>>IIUC this driver is similar to ftpm and svsm where the send is 
>>synchronous so having .status, .cancel, etc. set to 0 should be 
>>enough to call .recv() just after send() in tpm_try_transmit(). See 
>>commit 980a573621ea ("tpm: Make chip->{status,cancel,req_canceled} 
>>opt")
>The send callback would wait until the TPM_CC* command complete. We 
>don't need a poll.

Right, that's what I was saying too, send() is synchronous (as in ftpm 
and svsm). The polling in tpm_try_transmit() is already skipped since we 
are setting .status = 0, .req_complete_mask = 0, .req_complete_val = 0, 
etc. so IMHO this is exactly the same of ftpm and svsm, so we don't need 
to set TPM_CHIP_FLAG_IRQ.

Thanks,
Stefano


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

* Re: [PATCH v10 0/5] Add Loongson Security Engine chip driver
  2025-05-28  8:17     ` Huacai Chen
@ 2025-05-28  9:14       ` Yanteng Si
  2025-05-28 10:25         ` Huacai Chen
  0 siblings, 1 reply; 21+ messages in thread
From: Yanteng Si @ 2025-05-28  9:14 UTC (permalink / raw)
  To: Huacai Chen, Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity

在 5/28/25 4:17 PM, Huacai Chen 写道:
> On Wed, May 28, 2025 at 4:06 PM Qunqin Zhao <zhaoqunqin@loongson.cn> wrote:
>>
>>
>> 在 2025/5/28 下午3:17, Huacai Chen 写道:
>>> Hi, Qunqin,
>>>
>>> As I said before, why the patch "MAINTAINERS: Add entry for Loongson
>>> Security Module driver" is missing?
>>
>> Hi, Huacai
>>
>> https://lore.kernel.org/all/8e55801a-a46e-58d5-cf84-2ee8a733df9a@loongson.cn/
> Sorry, I missed this email. But if you put all files in one entry, you
> can merge Patch-3 and Patch-5 as the last patch (then you will also
> not meet the 5 patches limit).

We are cutting the foot to fit the shoe. Sigh...


Thanks,
Yanteng
> 
> Huacai
> 
>>
>> Thanks,
>>
>> Qunqin.
>>
>>>
>>> Huacai

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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  9:00       ` Stefano Garzarella
@ 2025-05-28  9:24         ` Qunqin Zhao
  2025-05-28  9:34           ` Qunqin Zhao
  2025-05-28  9:36           ` Stefano Garzarella
  0 siblings, 2 replies; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  9:24 UTC (permalink / raw)
  To: Stefano Garzarella
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen


在 2025/5/28 下午5:00, Stefano Garzarella 写道:
> On Wed, May 28, 2025 at 04:42:05PM +0800, Qunqin Zhao wrote:
>>
>> 在 2025/5/28 下午3:57, Stefano Garzarella 写道:
>>>> +    chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
>>>> +    if (IS_ERR(chip))
>>>> +        return PTR_ERR(chip);
>>>> +    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
>>>
>>> Why setting TPM_CHIP_FLAG_IRQ?
>>
>> When tpm_engine completes  TPM_CC* command,
>>
>> the hardware will indeed trigger an interrupt to the kernel.
>
> IIUC that is hidden by loongson_se_send_engine_cmd(), that for this 
> driver is completely synchronous, no?
>
>>
>>>
>>> IIUC this driver is similar to ftpm and svsm where the send is 
>>> synchronous so having .status, .cancel, etc. set to 0 should be 
>>> enough to call .recv() just after send() in tpm_try_transmit(). See 
>>> commit 980a573621ea ("tpm: Make chip->{status,cancel,req_canceled} 
>>> opt")
>> The send callback would wait until the TPM_CC* command complete. We 
>> don't need a poll.
>
> Right, that's what I was saying too, send() is synchronous (as in ftpm 
> and svsm). The polling in tpm_try_transmit() is already skipped since 
> we are setting .status = 0, .req_complete_mask = 0, .req_complete_val 
> = 0, etc. so IMHO this is exactly the same of ftpm and svsm, so we 
> don't need to set TPM_CHIP_FLAG_IRQ.

I see,  but why not skip polling directly in "if (chip->flags & 
TPM_CHIP_FLAG_IRQ)"  instead of do while?

And TPM_CHIP_FLAG_IRQ flag can remind us this hardware is "IRQ" not "POLL".

Thanks,

Qunqin.

>
> Thanks,
> Stefano


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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  9:24         ` Qunqin Zhao
@ 2025-05-28  9:34           ` Qunqin Zhao
  2025-05-28  9:53             ` Stefano Garzarella
  2025-05-28  9:36           ` Stefano Garzarella
  1 sibling, 1 reply; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-28  9:34 UTC (permalink / raw)
  To: Stefano Garzarella
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen


在 2025/5/28 下午5:24, Qunqin Zhao 写道:
>
> 在 2025/5/28 下午5:00, Stefano Garzarella 写道:
>> On Wed, May 28, 2025 at 04:42:05PM +0800, Qunqin Zhao wrote:
>>>
>>> 在 2025/5/28 下午3:57, Stefano Garzarella 写道:
>>>>> +    chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
>>>>> +    if (IS_ERR(chip))
>>>>> +        return PTR_ERR(chip);
>>>>> +    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
>>>>
>>>> Why setting TPM_CHIP_FLAG_IRQ?
>>>
>>> When tpm_engine completes  TPM_CC* command,
>>>
>>> the hardware will indeed trigger an interrupt to the kernel.
>>
>> IIUC that is hidden by loongson_se_send_engine_cmd(), that for this 
>> driver is completely synchronous, no?
>>
>>>
>>>>
>>>> IIUC this driver is similar to ftpm and svsm where the send is 
>>>> synchronous so having .status, .cancel, etc. set to 0 should be 
>>>> enough to call .recv() just after send() in tpm_try_transmit(). See 
>>>> commit 980a573621ea ("tpm: Make chip->{status,cancel,req_canceled} 
>>>> opt")
>>> The send callback would wait until the TPM_CC* command complete. We 
>>> don't need a poll.
>>
>> Right, that's what I was saying too, send() is synchronous (as in 
>> ftpm and svsm). The polling in tpm_try_transmit() is already skipped 
>> since we are setting .status = 0, .req_complete_mask = 0, 
>> .req_complete_val = 0, etc. so IMHO this is exactly the same of ftpm 
>> and svsm, so we don't need to set TPM_CHIP_FLAG_IRQ.
>
> I see,  but why not skip polling directly in "if (chip->flags & 
> TPM_CHIP_FLAG_IRQ)"  instead of do while?

I mean, why not skip polling directly in "if (chip->flags & 
TPM_CHIP_FLAG_IRQ)"?

And In my opinion, TPM_CHIP_FLAG_SYNC and TPM_CHIP_FLAG_IRQ are 
essentially the same, only with different names.

Thanks,

Qunqin

>
> And TPM_CHIP_FLAG_IRQ flag can remind us this hardware is "IRQ" not 
> "POLL".
>
> Thanks,
>
> Qunqin.
>
>>
>> Thanks,
>> Stefano


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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  9:24         ` Qunqin Zhao
  2025-05-28  9:34           ` Qunqin Zhao
@ 2025-05-28  9:36           ` Stefano Garzarella
  1 sibling, 0 replies; 21+ messages in thread
From: Stefano Garzarella @ 2025-05-28  9:36 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen

On Wed, 28 May 2025 at 11:25, Qunqin Zhao <zhaoqunqin@loongson.cn> wrote:
>
>
> 在 2025/5/28 下午5:00, Stefano Garzarella 写道:
> > On Wed, May 28, 2025 at 04:42:05PM +0800, Qunqin Zhao wrote:
> >>
> >> 在 2025/5/28 下午3:57, Stefano Garzarella 写道:
> >>>> +    chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
> >>>> +    if (IS_ERR(chip))
> >>>> +        return PTR_ERR(chip);
> >>>> +    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
> >>>
> >>> Why setting TPM_CHIP_FLAG_IRQ?
> >>
> >> When tpm_engine completes  TPM_CC* command,
> >>
> >> the hardware will indeed trigger an interrupt to the kernel.
> >
> > IIUC that is hidden by loongson_se_send_engine_cmd(), that for this
> > driver is completely synchronous, no?
> >
> >>
> >>>
> >>> IIUC this driver is similar to ftpm and svsm where the send is
> >>> synchronous so having .status, .cancel, etc. set to 0 should be
> >>> enough to call .recv() just after send() in tpm_try_transmit(). See
> >>> commit 980a573621ea ("tpm: Make chip->{status,cancel,req_canceled}
> >>> opt")
> >> The send callback would wait until the TPM_CC* command complete. We
> >> don't need a poll.
> >
> > Right, that's what I was saying too, send() is synchronous (as in ftpm
> > and svsm). The polling in tpm_try_transmit() is already skipped since
> > we are setting .status = 0, .req_complete_mask = 0, .req_complete_val
> > = 0, etc. so IMHO this is exactly the same of ftpm and svsm, so we
> > don't need to set TPM_CHIP_FLAG_IRQ.
>
> I see,  but why not skip polling directly in "if (chip->flags &
> TPM_CHIP_FLAG_IRQ)"  instead of do while?

This is exactly what I'm doing in the series I linked before [1] but
without leveraging TPM_CHIP_FLAG_IRQ's hack

>
> And TPM_CHIP_FLAG_IRQ flag can remind us this hardware is "IRQ" not "POLL".

But you're not handling IRQ through this driver, so for the tpm
interface sending tpm commands through this driver is not interrupt
based or needs polling, but it's synchronous, so this is why I'm
adding TPM_CHIP_FLAG_SYNC in [1] and I think I can include the changes
I did for ftpm and svsm also for this driver in that series.

So my suggestion in this patch is to do something similar of what we
already have for those driver, and we can set TPM_CHIP_FLAG_SYNC when
my series will be merged (or I'll include the changes if this series
will go first).

Thanks,
Stefano

[1] https://lore.kernel.org/linux-integrity/20250514134630.137621-1-sgarzare@redhat.com/

>
> Thanks,
>
> Qunqin.
>
> >
> > Thanks,
> > Stefano
>


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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  9:34           ` Qunqin Zhao
@ 2025-05-28  9:53             ` Stefano Garzarella
  2025-05-29  2:16               ` Qunqin Zhao
  0 siblings, 1 reply; 21+ messages in thread
From: Stefano Garzarella @ 2025-05-28  9:53 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen

On Wed, May 28, 2025 at 05:34:49PM +0800, Qunqin Zhao wrote:
>
>在 2025/5/28 下午5:24, Qunqin Zhao 写道:
>>
>>在 2025/5/28 下午5:00, Stefano Garzarella 写道:
>>>On Wed, May 28, 2025 at 04:42:05PM +0800, Qunqin Zhao wrote:
>>>>
>>>>在 2025/5/28 下午3:57, Stefano Garzarella 写道:
>>>>>>+    chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
>>>>>>+    if (IS_ERR(chip))
>>>>>>+        return PTR_ERR(chip);
>>>>>>+    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
>>>>>
>>>>>Why setting TPM_CHIP_FLAG_IRQ?
>>>>
>>>>When tpm_engine completes  TPM_CC* command,
>>>>
>>>>the hardware will indeed trigger an interrupt to the kernel.
>>>
>>>IIUC that is hidden by loongson_se_send_engine_cmd(), that for 
>>>this driver is completely synchronous, no?
>>>
>>>>
>>>>>
>>>>>IIUC this driver is similar to ftpm and svsm where the send is 
>>>>>synchronous so having .status, .cancel, etc. set to 0 should 
>>>>>be enough to call .recv() just after send() in 
>>>>>tpm_try_transmit(). See commit 980a573621ea ("tpm: Make 
>>>>>chip->{status,cancel,req_canceled} opt")
>>>>The send callback would wait until the TPM_CC* command complete. 
>>>>We don't need a poll.
>>>
>>>Right, that's what I was saying too, send() is synchronous (as in 
>>>ftpm and svsm). The polling in tpm_try_transmit() is already 
>>>skipped since we are setting .status = 0, .req_complete_mask = 0, 
>>>.req_complete_val = 0, etc. so IMHO this is exactly the same of 
>>>ftpm and svsm, so we don't need to set TPM_CHIP_FLAG_IRQ.
>>
>>I see,  but why not skip polling directly in "if (chip->flags & 
>>TPM_CHIP_FLAG_IRQ)"  instead of do while?
>
>I mean, why not skip polling directly in "if (chip->flags & 
>TPM_CHIP_FLAG_IRQ)"?
>
>And In my opinion, TPM_CHIP_FLAG_SYNC and TPM_CHIP_FLAG_IRQ are 
>essentially the same, only with different names.

When TPM_CHIP_FLAG_SYNC is defined, the .recv() is not invoked and 
.send() will send the command and retrieve the response. For some driver 
like ftpm this will save an extra copy/buffer.

Stefano


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

* Re: [PATCH v10 0/5] Add Loongson Security Engine chip driver
  2025-05-28  9:14       ` Yanteng Si
@ 2025-05-28 10:25         ` Huacai Chen
  0 siblings, 0 replies; 21+ messages in thread
From: Huacai Chen @ 2025-05-28 10:25 UTC (permalink / raw)
  To: Yanteng Si
  Cc: Qunqin Zhao, lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity

On Wed, May 28, 2025 at 5:15 PM Yanteng Si <si.yanteng@linux.dev> wrote:
>
> 在 5/28/25 4:17 PM, Huacai Chen 写道:
> > On Wed, May 28, 2025 at 4:06 PM Qunqin Zhao <zhaoqunqin@loongson.cn> wrote:
> >>
> >>
> >> 在 2025/5/28 下午3:17, Huacai Chen 写道:
> >>> Hi, Qunqin,
> >>>
> >>> As I said before, why the patch "MAINTAINERS: Add entry for Loongson
> >>> Security Module driver" is missing?
> >>
> >> Hi, Huacai
> >>
> >> https://lore.kernel.org/all/8e55801a-a46e-58d5-cf84-2ee8a733df9a@loongson.cn/
> > Sorry, I missed this email. But if you put all files in one entry, you
> > can merge Patch-3 and Patch-5 as the last patch (then you will also
> > not meet the 5 patches limit).
>
> We are cutting the foot to fit the shoe. Sigh...
No, the two patches really need to be squashed.

Huacai

>
>
> Thanks,
> Yanteng
> >
> > Huacai
> >
> >>
> >> Thanks,
> >>
> >> Qunqin.
> >>
> >>>
> >>> Huacai

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

* Re: [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device
  2025-05-28  9:53             ` Stefano Garzarella
@ 2025-05-29  2:16               ` Qunqin Zhao
  0 siblings, 0 replies; 21+ messages in thread
From: Qunqin Zhao @ 2025-05-29  2:16 UTC (permalink / raw)
  To: Stefano Garzarella
  Cc: lee, herbert, jarkko, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen


在 2025/5/28 下午5:53, Stefano Garzarella 写道:
> On Wed, May 28, 2025 at 05:34:49PM +0800, Qunqin Zhao wrote:
>>
>> 在 2025/5/28 下午5:24, Qunqin Zhao 写道:
>>>
>>> 在 2025/5/28 下午5:00, Stefano Garzarella 写道:
>>>> On Wed, May 28, 2025 at 04:42:05PM +0800, Qunqin Zhao wrote:
>>>>>
>>>>> 在 2025/5/28 下午3:57, Stefano Garzarella 写道:
>>>>>>> +    chip = tpmm_chip_alloc(dev, &tpm_loongson_ops);
>>>>>>> +    if (IS_ERR(chip))
>>>>>>> +        return PTR_ERR(chip);
>>>>>>> +    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_IRQ;
>>>>>>
>>>>>> Why setting TPM_CHIP_FLAG_IRQ?
>>>>>
>>>>> When tpm_engine completes  TPM_CC* command,
>>>>>
>>>>> the hardware will indeed trigger an interrupt to the kernel.
>>>>
>>>> IIUC that is hidden by loongson_se_send_engine_cmd(), that for this 
>>>> driver is completely synchronous, no?
>>>>
>>>>>
>>>>>>
>>>>>> IIUC this driver is similar to ftpm and svsm where the send is 
>>>>>> synchronous so having .status, .cancel, etc. set to 0 should be 
>>>>>> enough to call .recv() just after send() in tpm_try_transmit(). 
>>>>>> See commit 980a573621ea ("tpm: Make 
>>>>>> chip->{status,cancel,req_canceled} opt")
>>>>> The send callback would wait until the TPM_CC* command complete. 
>>>>> We don't need a poll.
>>>>
>>>> Right, that's what I was saying too, send() is synchronous (as in 
>>>> ftpm and svsm). The polling in tpm_try_transmit() is already 
>>>> skipped since we are setting .status = 0, .req_complete_mask = 0, 
>>>> .req_complete_val = 0, etc. so IMHO this is exactly the same of 
>>>> ftpm and svsm, so we don't need to set TPM_CHIP_FLAG_IRQ.
>>>
>>> I see,  but why not skip polling directly in "if (chip->flags & 
>>> TPM_CHIP_FLAG_IRQ)"  instead of do while?
>>
>> I mean, why not skip polling directly in "if (chip->flags & 
>> TPM_CHIP_FLAG_IRQ)"?
>>
>> And In my opinion, TPM_CHIP_FLAG_SYNC and TPM_CHIP_FLAG_IRQ are 
>> essentially the same, only with different names.
>
> When TPM_CHIP_FLAG_SYNC is defined, the .recv() is not invoked and 
> .send() will send the command and retrieve the response. For some 
> driver like ftpm this will save an extra copy/buffer.

I need to copy the data to the DMA data buffer. So my suggestion is to 
let the vendor specific driver  decide whether to use the SYNC or IRQ flag.

IRQ flag is fine for me.

Thanks,

Qunqin.

>
> Stefano


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

* Re: [PATCH v10 2/5] crypto: loongson - add Loongson RNG driver support
  2025-05-28  6:59 ` [PATCH v10 2/5] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
@ 2025-06-11  9:23   ` Herbert Xu
  2025-06-17  9:49     ` Qunqin Zhao
  0 siblings, 1 reply; 21+ messages in thread
From: Herbert Xu @ 2025-06-11  9:23 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, jarkko, linux-kernel, loongarch, davem, linux-crypto,
	peterhuewe, jgg, linux-integrity, Yinggang Gu, Huacai Chen

On Wed, May 28, 2025 at 02:59:41PM +0800, Qunqin Zhao wrote:
>
> +	if (!rng_devices.is_init) {
> +		ret = crypto_register_rng(&loongson_rng_alg);
> +		if (ret) {
> +			dev_err(&pdev->dev, "failed to register crypto(%d)\n", ret);
> +			return ret;
> +		}
> +		INIT_LIST_HEAD(&rng_devices.list);
> +		mutex_init(&rng_devices.lock);
> +		rng_devices.is_init = true;
> +	}

This doesn't look right.  What stops two devices from both entering
this code path when is_init == false?

Cheers,
-- 
Email: Herbert Xu <herbert@gondor.apana.org.au>
Home Page: http://gondor.apana.org.au/~herbert/
PGP Key: http://gondor.apana.org.au/~herbert/pubkey.txt

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

* Re: [PATCH v10 2/5] crypto: loongson - add Loongson RNG driver support
  2025-06-11  9:23   ` Herbert Xu
@ 2025-06-17  9:49     ` Qunqin Zhao
  0 siblings, 0 replies; 21+ messages in thread
From: Qunqin Zhao @ 2025-06-17  9:49 UTC (permalink / raw)
  To: Herbert Xu
  Cc: lee, jarkko, linux-kernel, loongarch, davem, linux-crypto,
	peterhuewe, jgg, linux-integrity, Yinggang Gu, Huacai Chen


在 2025/6/11 下午5:23, Herbert Xu 写道:
> On Wed, May 28, 2025 at 02:59:41PM +0800, Qunqin Zhao wrote:
>> +	if (!rng_devices.is_init) {
>> +		ret = crypto_register_rng(&loongson_rng_alg);
>> +		if (ret) {
>> +			dev_err(&pdev->dev, "failed to register crypto(%d)\n", ret);
>> +			return ret;
>> +		}
>> +		INIT_LIST_HEAD(&rng_devices.list);
>> +		mutex_init(&rng_devices.lock);
>> +		rng_devices.is_init = true;
>> +	}
> This doesn't look right.  What stops two devices from both entering
> this code path when is_init == false?

Will use __MUTEX_INITIALIZER  macro to statically initialize 
rng_devices. lock,

and then use this lock to stop two devices form both entering this code 
path.


Thanks,

Qunqin

>
> Cheers,


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

end of thread, other threads:[~2025-06-17  9:50 UTC | newest]

Thread overview: 21+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2025-05-28  6:59 [PATCH v10 0/5] Add Loongson Security Engine chip driver Qunqin Zhao
2025-05-28  6:59 ` [PATCH v10 1/5] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
2025-05-28  6:59 ` [PATCH v10 2/5] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
2025-06-11  9:23   ` Herbert Xu
2025-06-17  9:49     ` Qunqin Zhao
2025-05-28  6:59 ` [PATCH v10 3/5] MAINTAINERS: Add entry for Loongson crypto driver Qunqin Zhao
2025-05-28  6:59 ` [PATCH v10 4/5] tpm: Add a driver for Loongson TPM device Qunqin Zhao
2025-05-28  7:57   ` Stefano Garzarella
2025-05-28  8:42     ` Qunqin Zhao
2025-05-28  9:00       ` Stefano Garzarella
2025-05-28  9:24         ` Qunqin Zhao
2025-05-28  9:34           ` Qunqin Zhao
2025-05-28  9:53             ` Stefano Garzarella
2025-05-29  2:16               ` Qunqin Zhao
2025-05-28  9:36           ` Stefano Garzarella
2025-05-28  7:17 ` [PATCH v10 0/5] Add Loongson Security Engine chip driver Huacai Chen
2025-05-28  7:42   ` Yanteng Si
2025-05-28  8:05   ` Qunqin Zhao
2025-05-28  8:17     ` Huacai Chen
2025-05-28  9:14       ` Yanteng Si
2025-05-28 10:25         ` Huacai Chen

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