loongarch.lists.linux.dev archive mirror
 help / color / mirror / Atom feed
* [PATCH v12 0/4] Add Loongson Security Engine chip driver
@ 2025-07-05  7:20 Qunqin Zhao
  2025-07-05  7:20 ` [PATCH v12 1/4] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
                   ` (5 more replies)
  0 siblings, 6 replies; 14+ messages in thread
From: Qunqin Zhao @ 2025-07-05  7:20 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.

v12: "loongson-tpm" -> "tmp_loongson"

v11: Put all updates to the MAINTAINERS in one patch
     crypto: statically initialize rng_devices.lock, use this lock in
             loongson_rng_probe().

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 the
    concepts of "egnine" and "command" may be better.

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: mfd: Registered "ls6000se-rng" device in mfd driver
    tpm: Prefix all with tpm_loongson instead of tpm_lsse.
         Replace all "ls6000se" with "loongson"

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

v3: Put the updates to the MAINTAINERS in a separate patch.
    tpm: Added reminder about Loongson security engine to git log.

v2: Removed misc driver. Added tpm driver.

Qunqin Zhao (4):
  mfd: Add support for Loongson Security Engine chip controller
  crypto: loongson - add Loongson RNG driver support
  tpm: Add a driver for Loongson TPM device
  MAINTAINERS: Add entry for Loongson Security Engine drivers

 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 | 209 ++++++++++++++++++++
 drivers/mfd/Kconfig                    |  11 ++
 drivers/mfd/Makefile                   |   2 +
 drivers/mfd/loongson-se.c              | 253 +++++++++++++++++++++++++
 include/linux/mfd/loongson-se.h        |  53 ++++++
 13 files changed, 639 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: a79a588fc1761dc12a3064fc2f648ae66cea3c5a
-- 
2.45.2


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

* [PATCH v12 1/4] mfd: Add support for Loongson Security Engine chip controller
  2025-07-05  7:20 [PATCH v12 0/4] Add Loongson Security Engine chip driver Qunqin Zhao
@ 2025-07-05  7:20 ` Qunqin Zhao
  2025-07-05  7:20 ` [PATCH v12 2/4] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
                   ` (4 subsequent siblings)
  5 siblings, 0 replies; 14+ messages in thread
From: Qunqin Zhao @ 2025-07-05  7:20 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>
---
 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 6fb3768e3..1135f3144 100644
--- a/drivers/mfd/Kconfig
+++ b/drivers/mfd/Kconfig
@@ -2410,6 +2410,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 79495f9f3..695656667 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -294,3 +294,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..3902ba377
--- /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 = "tpm_loongson" },
+};
+
+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] 14+ messages in thread

* [PATCH v12 2/4] crypto: loongson - add Loongson RNG driver support
  2025-07-05  7:20 [PATCH v12 0/4] Add Loongson Security Engine chip driver Qunqin Zhao
  2025-07-05  7:20 ` [PATCH v12 1/4] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
@ 2025-07-05  7:20 ` Qunqin Zhao
  2025-08-19 12:55   ` Lee Jones
  2025-07-05  7:20 ` [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device Qunqin Zhao
                   ` (3 subsequent siblings)
  5 siblings, 1 reply; 14+ messages in thread
From: Qunqin Zhao @ 2025-07-05  7:20 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>
---
 drivers/crypto/Kconfig                 |   1 +
 drivers/crypto/Makefile                |   1 +
 drivers/crypto/loongson/Kconfig        |   5 +
 drivers/crypto/loongson/Makefile       |   1 +
 drivers/crypto/loongson/loongson-rng.c | 209 +++++++++++++++++++++++++
 5 files changed, 217 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 9f8a3a5be..f6117bc77 100644
--- a/drivers/crypto/Kconfig
+++ b/drivers/crypto/Kconfig
@@ -827,6 +827,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..3a4940260
--- /dev/null
+++ b/drivers/crypto/loongson/loongson-rng.c
@@ -0,0 +1,209 @@
+// 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 registered;
+};
+
+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 = {
+	.lock = __MUTEX_INITIALIZER(rng_devices.lock),
+	.list = LIST_HEAD_INIT(rng_devices.list),
+};
+
+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 int loongson_rng_probe(struct platform_device *pdev)
+{
+	struct loongson_rng_cmd *cmd;
+	struct loongson_rng *rng;
+	int ret = 0;
+
+	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;
+	mutex_init(&rng->lock);
+
+	mutex_lock(&rng_devices.lock);
+
+	if (!rng_devices.registered) {
+		ret = crypto_register_rng(&loongson_rng_alg);
+		if (ret) {
+			dev_err(&pdev->dev, "failed to register crypto(%d)\n", ret);
+			goto out;
+		}
+		rng_devices.registered = 1;
+	}
+
+	list_add_tail(&rng->list, &rng_devices.list);
+out:
+	mutex_unlock(&rng_devices.lock);
+
+	return ret;
+}
+
+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] 14+ messages in thread

* [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device
  2025-07-05  7:20 [PATCH v12 0/4] Add Loongson Security Engine chip driver Qunqin Zhao
  2025-07-05  7:20 ` [PATCH v12 1/4] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
  2025-07-05  7:20 ` [PATCH v12 2/4] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
@ 2025-07-05  7:20 ` Qunqin Zhao
  2025-07-07  9:48   ` Stefano Garzarella
  2025-07-19 12:09   ` Jarkko Sakkinen
  2025-07-05  7:20 ` [PATCH v12 4/4] MAINTAINERS: Add entry for Loongson Security Engine drivers Qunqin Zhao
                   ` (2 subsequent siblings)
  5 siblings, 2 replies; 14+ messages in thread
From: Qunqin Zhao @ 2025-07-05  7:20 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>
---
 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..a4ec23639
--- /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  = "tpm_loongson",
+	},
+};
+module_platform_driver(tpm_loongson);
+
+MODULE_ALIAS("platform:tpm_loongson");
+MODULE_LICENSE("GPL");
+MODULE_DESCRIPTION("Loongson TPM driver");
-- 
2.45.2


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

* [PATCH v12 4/4] MAINTAINERS: Add entry for Loongson Security Engine drivers
  2025-07-05  7:20 [PATCH v12 0/4] Add Loongson Security Engine chip driver Qunqin Zhao
                   ` (2 preceding siblings ...)
  2025-07-05  7:20 ` [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device Qunqin Zhao
@ 2025-07-05  7:20 ` Qunqin Zhao
  2025-09-02 11:32 ` [PATCH v12 0/4] Add Loongson Security Engine chip driver Lee Jones
  2025-09-02 12:42 ` [GIT PULL] Immutable branch between MFD, Char and Crypto due for the v6.18 merge window Lee Jones
  5 siblings, 0 replies; 14+ messages in thread
From: Qunqin Zhao @ 2025-07-05  7:20 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 Security Engine drivers in the
list of maintainers.

Signed-off-by: Qunqin Zhao <zhaoqunqin@loongson.cn>
Reviewed-by: Huacai Chen <chenhuacai@loongson.cn>
---
 MAINTAINERS | 9 +++++++++
 1 file changed, 9 insertions(+)

diff --git a/MAINTAINERS b/MAINTAINERS
index fad6cb025..1ccb267ce 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -14153,6 +14153,15 @@ S:	Maintained
 F:	Documentation/devicetree/bindings/pwm/loongson,ls7a-pwm.yaml
 F:	drivers/pwm/pwm-loongson.c
 
+LOONGSON SECURITY ENGINE DRIVERS
+M:	Qunqin Zhao <zhaoqunqin@loongson.cn>
+L:	linux-crypto@vger.kernel.org
+S:	Maintained
+F:	drivers/char/tpm_loongson.c
+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] 14+ messages in thread

* Re: [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device
  2025-07-05  7:20 ` [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device Qunqin Zhao
@ 2025-07-07  9:48   ` Stefano Garzarella
  2025-07-26  7:05     ` Qunqin Zhao
  2025-07-19 12:09   ` Jarkko Sakkinen
  1 sibling, 1 reply; 14+ messages in thread
From: Stefano Garzarella @ 2025-07-07  9:48 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 Sat, Jul 05, 2025 at 03:20:44PM +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>
>---
> 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

TPM_CHIP_FLAG_SYNC support is now merged in linux-tpmdd/next tree, so 
IMHO this driver can also set it and implement a synchronous send() in 
this way (untested):

diff --git a/drivers/char/tpm/tpm_loongson.c b/drivers/char/tpm/tpm_loongson.c
index a4ec23639911..0e8eb8cee13c 100644
--- a/drivers/char/tpm/tpm_loongson.c
+++ b/drivers/char/tpm/tpm_loongson.c
@@ -15,36 +15,35 @@ struct tpm_loongson_cmd {
  	u32 pad[5];
  };

-static int tpm_loongson_recv(struct tpm_chip *chip, u8 *buf, size_t count)
+static int tpm_loongson_send(struct tpm_chip *chip, u8 *buf, size_t bufsiz,
+			     size_t cmd_len)
  {
  	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;
+	struct tpm_loongson_cmd *cmd = tpm_engine->command;
+	struct tpm_loongson_cmd *cmd_ret;
+	int ret;

-	memcpy(buf, tpm_engine->data_buffer, cmd_ret->data_len);
+	if (cmd_len > tpm_engine->buffer_size)
+		return -E2BIG;

-	return cmd_ret->data_len;
-}
+	cmd->data_len = cmd_len;
+	memcpy(tpm_engine->data_buffer, buf, cmd_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;
+	ret = loongson_se_send_engine_cmd(tpm_engine);
+	if (ret)
+		return ret;

-	if (count > tpm_engine->buffer_size)
-		return -E2BIG;
+	cmd_ret = tpm_engine->command_ret;
+	if (cmd_ret->data_len > bufsiz)
+		return -EIO;

-	cmd->data_len = count;
-	memcpy(tpm_engine->data_buffer, buf, count);
+	memcpy(buf, tpm_engine->data_buffer, cmd_ret->data_len);

-	return loongson_se_send_engine_cmd(tpm_engine);
+	return cmd_ret->data_len;
  }

  static const struct tpm_class_ops tpm_loongson_ops = {
  	.flags = TPM_OPS_AUTO_STARTUP,
-	.recv = tpm_loongson_recv,
  	.send = tpm_loongson_send,
  };

@@ -65,7 +64,7 @@ static int tpm_loongson_probe(struct platform_device *pdev)
  	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;
+	chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_SYNC;
  	dev_set_drvdata(&chip->dev, tpm_engine);

  	return tpm_chip_register(chip);

Thanks,
Stefano

>
>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..a4ec23639
>--- /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  = "tpm_loongson",
>+	},
>+};
>+module_platform_driver(tpm_loongson);
>+
>+MODULE_ALIAS("platform:tpm_loongson");
>+MODULE_LICENSE("GPL");
>+MODULE_DESCRIPTION("Loongson TPM driver");
>-- 
>2.45.2
>
>


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

* Re: [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device
  2025-07-05  7:20 ` [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device Qunqin Zhao
  2025-07-07  9:48   ` Stefano Garzarella
@ 2025-07-19 12:09   ` Jarkko Sakkinen
  2025-07-20  1:05     ` Huacai Chen
  1 sibling, 1 reply; 14+ messages in thread
From: Jarkko Sakkinen @ 2025-07-19 12:09 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: lee, herbert, linux-kernel, loongarch, davem, linux-crypto,
	peterhuewe, jgg, linux-integrity, Yinggang Gu, Huacai Chen

On Sat, Jul 05, 2025 at 03:20:44PM +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>
> ---
>  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..a4ec23639
> --- /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  = "tpm_loongson",
> +	},
> +};
> +module_platform_driver(tpm_loongson);
> +
> +MODULE_ALIAS("platform:tpm_loongson");
> +MODULE_LICENSE("GPL");
> +MODULE_DESCRIPTION("Loongson TPM driver");
> -- 
> 2.45.2
> 

Reviewed-by: Jarkko Sakkinen <jarkko@kernel.org>

Can you take this through loongson tree? It's highly unlikely to
conflict with anything.

BR, Jarkko

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

* Re: [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device
  2025-07-19 12:09   ` Jarkko Sakkinen
@ 2025-07-20  1:05     ` Huacai Chen
  0 siblings, 0 replies; 14+ messages in thread
From: Huacai Chen @ 2025-07-20  1:05 UTC (permalink / raw)
  To: Jarkko Sakkinen
  Cc: Qunqin Zhao, lee, herbert, linux-kernel, loongarch, davem,
	linux-crypto, peterhuewe, jgg, linux-integrity, Yinggang Gu,
	Huacai Chen

Hi, Jarkko,

On Sat, Jul 19, 2025 at 8:09 PM Jarkko Sakkinen <jarkko@kernel.org> wrote:
>
> On Sat, Jul 05, 2025 at 03:20:44PM +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>
> > ---
> >  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..a4ec23639
> > --- /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  = "tpm_loongson",
> > +     },
> > +};
> > +module_platform_driver(tpm_loongson);
> > +
> > +MODULE_ALIAS("platform:tpm_loongson");
> > +MODULE_LICENSE("GPL");
> > +MODULE_DESCRIPTION("Loongson TPM driver");
> > --
> > 2.45.2
> >
>
> Reviewed-by: Jarkko Sakkinen <jarkko@kernel.org>
>
> Can you take this through loongson tree? It's highly unlikely to
> conflict with anything.
It is better to get upstream through the tpmdd tree, and Stefano's
suggestions should be addressed first.

Huacai

>
> BR, Jarkko
>

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

* Re: [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device
  2025-07-07  9:48   ` Stefano Garzarella
@ 2025-07-26  7:05     ` Qunqin Zhao
  0 siblings, 0 replies; 14+ messages in thread
From: Qunqin Zhao @ 2025-07-26  7:05 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/7/7 下午5:48, Stefano Garzarella 写道:
> On Sat, Jul 05, 2025 at 03:20:44PM +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>
>> ---
>> 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
>
> TPM_CHIP_FLAG_SYNC support is now merged in linux-tpmdd/next tree, so 
> IMHO this driver can also set it and implement a synchronous send() in 
> this way (untested):
>
> diff --git a/drivers/char/tpm/tpm_loongson.c 
> b/drivers/char/tpm/tpm_loongson.c

Thank you very much, but I prefer send()+recv().

Qunqin.

> index a4ec23639911..0e8eb8cee13c 100644
> --- a/drivers/char/tpm/tpm_loongson.c
> +++ b/drivers/char/tpm/tpm_loongson.c
> @@ -15,36 +15,35 @@ struct tpm_loongson_cmd {
>      u32 pad[5];
>  };
>
> -static int tpm_loongson_recv(struct tpm_chip *chip, u8 *buf, size_t 
> count)
> +static int tpm_loongson_send(struct tpm_chip *chip, u8 *buf, size_t 
> bufsiz,
> +                 size_t cmd_len)
>  {
>      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;
> +    struct tpm_loongson_cmd *cmd = tpm_engine->command;
> +    struct tpm_loongson_cmd *cmd_ret;
> +    int ret;
>
> -    memcpy(buf, tpm_engine->data_buffer, cmd_ret->data_len);
> +    if (cmd_len > tpm_engine->buffer_size)
> +        return -E2BIG;
>
> -    return cmd_ret->data_len;
> -}
> +    cmd->data_len = cmd_len;
> +    memcpy(tpm_engine->data_buffer, buf, cmd_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;
> +    ret = loongson_se_send_engine_cmd(tpm_engine);
> +    if (ret)
> +        return ret;
>
> -    if (count > tpm_engine->buffer_size)
> -        return -E2BIG;
> +    cmd_ret = tpm_engine->command_ret;
> +    if (cmd_ret->data_len > bufsiz)
> +        return -EIO;
>
> -    cmd->data_len = count;
> -    memcpy(tpm_engine->data_buffer, buf, count);
> +    memcpy(buf, tpm_engine->data_buffer, cmd_ret->data_len);
>
> -    return loongson_se_send_engine_cmd(tpm_engine);
> +    return cmd_ret->data_len;
>  }
>
>  static const struct tpm_class_ops tpm_loongson_ops = {
>      .flags = TPM_OPS_AUTO_STARTUP,
> -    .recv = tpm_loongson_recv,
>      .send = tpm_loongson_send,
>  };
>
> @@ -65,7 +64,7 @@ static int tpm_loongson_probe(struct platform_device 
> *pdev)
>      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;
> +    chip->flags = TPM_CHIP_FLAG_TPM2 | TPM_CHIP_FLAG_SYNC;
>      dev_set_drvdata(&chip->dev, tpm_engine);
>
>      return tpm_chip_register(chip);
>
> Thanks,
> Stefano
>
>>
>> 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..a4ec23639
>> --- /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  = "tpm_loongson",
>> +    },
>> +};
>> +module_platform_driver(tpm_loongson);
>> +
>> +MODULE_ALIAS("platform:tpm_loongson");
>> +MODULE_LICENSE("GPL");
>> +MODULE_DESCRIPTION("Loongson TPM driver");
>> -- 
>> 2.45.2
>>
>>


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

* Re: [PATCH v12 2/4] crypto: loongson - add Loongson RNG driver support
  2025-07-05  7:20 ` [PATCH v12 2/4] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
@ 2025-08-19 12:55   ` Lee Jones
  2025-08-20  2:33     ` Herbert Xu
  0 siblings, 1 reply; 14+ messages in thread
From: Lee Jones @ 2025-08-19 12:55 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: herbert, jarkko, linux-kernel, loongarch, davem, linux-crypto,
	peterhuewe, jgg, linux-integrity, Yinggang Gu, Huacai Chen

On Sat, 05 Jul 2025, Qunqin Zhao wrote:

> 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>
> ---
>  drivers/crypto/Kconfig                 |   1 +
>  drivers/crypto/Makefile                |   1 +
>  drivers/crypto/loongson/Kconfig        |   5 +
>  drivers/crypto/loongson/Makefile       |   1 +
>  drivers/crypto/loongson/loongson-rng.c | 209 +++++++++++++++++++++++++
>  5 files changed, 217 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 9f8a3a5be..f6117bc77 100644
> --- a/drivers/crypto/Kconfig
> +++ b/drivers/crypto/Kconfig
> @@ -827,6 +827,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..3a4940260
> --- /dev/null
> +++ b/drivers/crypto/loongson/loongson-rng.c
> @@ -0,0 +1,209 @@
> +// 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>

This depends on the first patch in the series.

Does this one have an Ack?

-- 
Lee Jones [李琼斯]

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

* Re: [PATCH v12 2/4] crypto: loongson - add Loongson RNG driver support
  2025-08-19 12:55   ` Lee Jones
@ 2025-08-20  2:33     ` Herbert Xu
  0 siblings, 0 replies; 14+ messages in thread
From: Herbert Xu @ 2025-08-20  2:33 UTC (permalink / raw)
  To: Lee Jones
  Cc: Qunqin Zhao, jarkko, linux-kernel, loongarch, davem, linux-crypto,
	peterhuewe, jgg, linux-integrity, Yinggang Gu, Huacai Chen

On Tue, Aug 19, 2025 at 01:55:18PM +0100, Lee Jones wrote:
>
> This depends on the first patch in the series.
> 
> Does this one have an Ack?

I thought I had acked it already.

Acked-by: Herbert Xu <herbert@gondor.apana.org.au>

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] 14+ messages in thread

* Re: [PATCH v12 0/4] Add Loongson Security Engine chip driver
  2025-07-05  7:20 [PATCH v12 0/4] Add Loongson Security Engine chip driver Qunqin Zhao
                   ` (3 preceding siblings ...)
  2025-07-05  7:20 ` [PATCH v12 4/4] MAINTAINERS: Add entry for Loongson Security Engine drivers Qunqin Zhao
@ 2025-09-02 11:32 ` Lee Jones
  2025-09-02 11:33   ` Lee Jones
  2025-09-02 12:42 ` [GIT PULL] Immutable branch between MFD, Char and Crypto due for the v6.18 merge window Lee Jones
  5 siblings, 1 reply; 14+ messages in thread
From: Lee Jones @ 2025-09-02 11:32 UTC (permalink / raw)
  To: lee, herbert, jarkko, Qunqin Zhao
  Cc: linux-kernel, loongarch, davem, linux-crypto, peterhuewe, jgg,
	linux-integrity

On Sat, 05 Jul 2025 15:20:41 +0800, Qunqin Zhao 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.
> 
> [...]

Applied, thanks!

[1/4] mfd: Add support for Loongson Security Engine chip controller
      commit: e551fa3159e3050c26ff010c3b595b45d7eb071a
[2/4] crypto: loongson - add Loongson RNG driver support
      commit: 766b2d724c8df071031412eea902b566a0049c31
[3/4] tpm: Add a driver for Loongson TPM device
      commit: 5c83b07df9c5a6e063328c5b885de79f8e8f0263
[4/4] MAINTAINERS: Add entry for Loongson Security Engine drivers
      commit: 74fddd5fbab879a7d039d9fb49af923927a64811

--
Lee Jones [李琼斯]


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

* Re: [PATCH v12 0/4] Add Loongson Security Engine chip driver
  2025-09-02 11:32 ` [PATCH v12 0/4] Add Loongson Security Engine chip driver Lee Jones
@ 2025-09-02 11:33   ` Lee Jones
  0 siblings, 0 replies; 14+ messages in thread
From: Lee Jones @ 2025-09-02 11:33 UTC (permalink / raw)
  To: herbert, jarkko, Qunqin Zhao
  Cc: linux-kernel, loongarch, davem, linux-crypto, peterhuewe, jgg,
	linux-integrity

On Tue, 02 Sep 2025, Lee Jones wrote:

> On Sat, 05 Jul 2025 15:20:41 +0800, Qunqin Zhao 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.
> > 
> > [...]
> 
> Applied, thanks!
> 
> [1/4] mfd: Add support for Loongson Security Engine chip controller
>       commit: e551fa3159e3050c26ff010c3b595b45d7eb071a
> [2/4] crypto: loongson - add Loongson RNG driver support
>       commit: 766b2d724c8df071031412eea902b566a0049c31
> [3/4] tpm: Add a driver for Loongson TPM device
>       commit: 5c83b07df9c5a6e063328c5b885de79f8e8f0263
> [4/4] MAINTAINERS: Add entry for Loongson Security Engine drivers
>       commit: 74fddd5fbab879a7d039d9fb49af923927a64811

Submitted for testing.  I'll send out a PR once successful.

Note to self: ib-mfd-char-crypto-6.18

-- 
Lee Jones [李琼斯]

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

* [GIT PULL] Immutable branch between MFD, Char and Crypto due for the v6.18 merge window
  2025-07-05  7:20 [PATCH v12 0/4] Add Loongson Security Engine chip driver Qunqin Zhao
                   ` (4 preceding siblings ...)
  2025-09-02 11:32 ` [PATCH v12 0/4] Add Loongson Security Engine chip driver Lee Jones
@ 2025-09-02 12:42 ` Lee Jones
  5 siblings, 0 replies; 14+ messages in thread
From: Lee Jones @ 2025-09-02 12:42 UTC (permalink / raw)
  To: Qunqin Zhao
  Cc: herbert, jarkko, linux-kernel, loongarch, davem, linux-crypto,
	peterhuewe, jgg, linux-integrity

Enjoy!

The following changes since commit 8f5ae30d69d7543eee0d70083daf4de8fe15d585:

  Linux 6.17-rc1 (2025-08-10 19:41:16 +0300)

are available in the Git repository at:

  git://git.kernel.org/pub/scm/linux/kernel/git/lee/mfd.git ib-mfd-char-crypto-v6.18

for you to fetch changes up to 74fddd5fbab879a7d039d9fb49af923927a64811:

  MAINTAINERS: Add entry for Loongson Security Engine drivers (2025-09-02 12:29:57 +0100)

----------------------------------------------------------------
Immutable branch between MFD, Char and Crypto due for the v6.18 merge window

----------------------------------------------------------------
Qunqin Zhao (4):
      mfd: Add support for Loongson Security Engine chip controller
      crypto: loongson - add Loongson RNG driver support
      tpm: Add a driver for Loongson TPM device
      MAINTAINERS: Add entry for Loongson Security Engine drivers

 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 | 209 +++++++++++++++++++++++++++
 drivers/mfd/Kconfig                    |  11 ++
 drivers/mfd/Makefile                   |   2 +
 drivers/mfd/loongson-se.c              | 253 +++++++++++++++++++++++++++++++++
 include/linux/mfd/loongson-se.h        |  53 +++++++
 13 files changed, 639 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

-- 
Lee Jones [李琼斯]

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

end of thread, other threads:[~2025-09-02 12:42 UTC | newest]

Thread overview: 14+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2025-07-05  7:20 [PATCH v12 0/4] Add Loongson Security Engine chip driver Qunqin Zhao
2025-07-05  7:20 ` [PATCH v12 1/4] mfd: Add support for Loongson Security Engine chip controller Qunqin Zhao
2025-07-05  7:20 ` [PATCH v12 2/4] crypto: loongson - add Loongson RNG driver support Qunqin Zhao
2025-08-19 12:55   ` Lee Jones
2025-08-20  2:33     ` Herbert Xu
2025-07-05  7:20 ` [PATCH v12 3/4] tpm: Add a driver for Loongson TPM device Qunqin Zhao
2025-07-07  9:48   ` Stefano Garzarella
2025-07-26  7:05     ` Qunqin Zhao
2025-07-19 12:09   ` Jarkko Sakkinen
2025-07-20  1:05     ` Huacai Chen
2025-07-05  7:20 ` [PATCH v12 4/4] MAINTAINERS: Add entry for Loongson Security Engine drivers Qunqin Zhao
2025-09-02 11:32 ` [PATCH v12 0/4] Add Loongson Security Engine chip driver Lee Jones
2025-09-02 11:33   ` Lee Jones
2025-09-02 12:42 ` [GIT PULL] Immutable branch between MFD, Char and Crypto due for the v6.18 merge window Lee Jones

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