* [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM
@ 2012-08-27 23:36 Paul Walmsley
2012-08-27 23:36 ` [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data Paul Walmsley
` (5 more replies)
0 siblings, 6 replies; 11+ messages in thread
From: Paul Walmsley @ 2012-08-27 23:36 UTC (permalink / raw)
To: linux-omap, Herbert Xu, linux-arm-kernel, Matt Mackall
This series converts the OMAP hardware random number generator driver
to use runtime PM. Hardware integration data is added for OMAP2xxx
systems. I'm pretty sure this device is available on other OMAP chips
too, but may require some experimentation with the integration details.
There are still a few rough edges with this series. Something is
still not right with the reset behavior on OMAP2430, at least. But it
would be good to get acks from the hwrng folks for the three patches that
touch files in that directory. Will continue with the testing process
here.
- Paul
---
Paul Walmsley (5):
ARM: OMAP2/3: hwmod: add RNG integration data
hwrng: OMAP: store per-device data in per-device variables, not file statics
hwrng: OMAP: convert to use runtime PM
ARM: OMAP: split OMAP1, OMAP2+ RNG device registration
hwrng: OMAP: remove SoC restrictions from driver registration
arch/arm/mach-omap1/devices.c | 28 +++++
arch/arm/mach-omap2/devices.c | 18 +++
arch/arm/mach-omap2/omap_hwmod_2420_data.c | 1
arch/arm/mach-omap2/omap_hwmod_2430_data.c | 1
.../mach-omap2/omap_hwmod_2xxx_interconnect_data.c | 17 +++
arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c | 37 ++++++
arch/arm/mach-omap2/omap_hwmod_common_data.h | 5 -
arch/arm/plat-omap/Makefile | 3
arch/arm/plat-omap/devices.c | 92 ---------------
drivers/char/hw_random/omap-rng.c | 121 ++++++++++++--------
10 files changed, 176 insertions(+), 147 deletions(-)
delete mode 100644 arch/arm/plat-omap/devices.c
^ permalink raw reply [flat|nested] 11+ messages in thread
* [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data
2012-08-27 23:36 [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Paul Walmsley
@ 2012-08-27 23:36 ` Paul Walmsley
2012-09-19 1:13 ` Paul Walmsley
2012-08-27 23:36 ` [PATCH 2/5] hwrng: OMAP: store per-device data in per-device variables, not file statics Paul Walmsley
` (4 subsequent siblings)
5 siblings, 1 reply; 11+ messages in thread
From: Paul Walmsley @ 2012-08-27 23:36 UTC (permalink / raw)
To: linux-omap, linux-arm-kernel
Add integration data for the hardware random number generator IP block
on some OMAP SoCs. This appears to be present on OMAP2xxx and OMAP3xxx
SoCs, although it is not so easy to tell. It may also be present on
other OMAP2+ SoCs.
Signed-off-by: Paul Walmsley <paul@pwsan.com>
---
arch/arm/mach-omap2/omap_hwmod_2420_data.c | 1 +
arch/arm/mach-omap2/omap_hwmod_2430_data.c | 1 +
.../mach-omap2/omap_hwmod_2xxx_interconnect_data.c | 17 +++++++++
arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c | 37 ++++++++++++++++++++
arch/arm/mach-omap2/omap_hwmod_common_data.h | 5 ++-
5 files changed, 59 insertions(+), 2 deletions(-)
diff --git a/arch/arm/mach-omap2/omap_hwmod_2420_data.c b/arch/arm/mach-omap2/omap_hwmod_2420_data.c
index 50cfab6..5a53287 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2420_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2420_data.c
@@ -587,6 +587,7 @@ static struct omap_hwmod_ocp_if *omap2420_hwmod_ocp_ifs[] __initdata = {
&omap2420_l4_core__mcbsp1,
&omap2420_l4_core__mcbsp2,
&omap2420_l4_core__msdi1,
+ &omap2xxx_l4_core__rng,
&omap2420_l4_core__hdq1w,
&omap2420_l4_wkup__counter_32k,
NULL,
diff --git a/arch/arm/mach-omap2/omap_hwmod_2430_data.c b/arch/arm/mach-omap2/omap_hwmod_2430_data.c
index 58b5bc1..256d8f6 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2430_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2430_data.c
@@ -947,6 +947,7 @@ static struct omap_hwmod_ocp_if *omap2430_hwmod_ocp_ifs[] __initdata = {
&omap2430_l4_core__mcbsp4,
&omap2430_l4_core__mcbsp5,
&omap2430_l4_core__hdq1w,
+ &omap2xxx_l4_core__rng,
&omap2430_l4_wkup__counter_32k,
NULL,
};
diff --git a/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c b/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
index 5178e40..14dc5ca 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
@@ -129,6 +129,15 @@ struct omap_hwmod_addr_space omap2xxx_mcbsp2_addrs[] = {
{ }
};
+static struct omap_hwmod_addr_space omap2_rng_addr_space[] = {
+ {
+ .pa_start = 0x480a0000,
+ .pa_end = 0x480a004f,
+ .flags = ADDR_TYPE_RT
+ },
+ { }
+};
+
/*
* Common interconnect data
*/
@@ -372,3 +381,11 @@ struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_venc = {
.user = OCP_USER_MPU | OCP_USER_SDMA,
};
+/* l4_core -> rng */
+struct omap_hwmod_ocp_if omap2xxx_l4_core__rng = {
+ .master = &omap2xxx_l4_core_hwmod,
+ .slave = &omap2xxx_rng_hwmod,
+ .clk = "l4_ck",
+ .addr = omap2_rng_addr_space,
+ .user = OCP_USER_MPU | OCP_USER_SDMA,
+};
diff --git a/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c b/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
index afad69c..06a37db 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
@@ -745,3 +745,40 @@ struct omap_hwmod omap2xxx_counter_32k_hwmod = {
},
.class = &omap2xxx_counter_hwmod_class,
};
+
+/* RNG */
+
+static struct omap_hwmod_class_sysconfig omap2_rng_sysc = {
+ .rev_offs = 0x3c,
+ .sysc_offs = 0x40,
+ .syss_offs = 0x44,
+ .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE |
+ SYSS_HAS_RESET_STATUS),
+ .sysc_fields = &omap_hwmod_sysc_type1,
+};
+
+static struct omap_hwmod_class omap2_rng_hwmod_class = {
+ .name = "rng",
+ .sysc = &omap2_rng_sysc,
+};
+
+static struct omap_hwmod_irq_info omap2_rng_mpu_irqs[] = {
+ { .irq = 52 },
+ { .irq = -1 }
+};
+
+struct omap_hwmod omap2xxx_rng_hwmod = {
+ .name = "rng",
+ .mpu_irqs = omap2_rng_mpu_irqs,
+ .main_clk = "l4_ck",
+ .prcm = {
+ .omap2 = {
+ .module_offs = CORE_MOD,
+ .prcm_reg_id = 4,
+ .module_bit = OMAP24XX_EN_RNG_SHIFT,
+ .idlest_reg_id = 4,
+ .idlest_idle_bit = OMAP24XX_ST_RNG_SHIFT,
+ },
+ },
+ .class = &omap2_rng_hwmod_class,
+};
diff --git a/arch/arm/mach-omap2/omap_hwmod_common_data.h b/arch/arm/mach-omap2/omap_hwmod_common_data.h
index e7e8eea..4363610 100644
--- a/arch/arm/mach-omap2/omap_hwmod_common_data.h
+++ b/arch/arm/mach-omap2/omap_hwmod_common_data.h
@@ -2,9 +2,8 @@
* omap_hwmod_common_data.h - OMAP hwmod common macros and declarations
*
* Copyright (C) 2010-2011 Nokia Corporation
+ * Copyright (C) 2010-2012 Texas Instruments, Inc.
* Paul Walmsley
- *
- * Copyright (C) 2010-2011 Texas Instruments, Inc.
* Benoît Cousson
*
* This program is free software; you can redistribute it and/or modify
@@ -76,6 +75,7 @@ extern struct omap_hwmod omap2xxx_gpio4_hwmod;
extern struct omap_hwmod omap2xxx_mcspi1_hwmod;
extern struct omap_hwmod omap2xxx_mcspi2_hwmod;
extern struct omap_hwmod omap2xxx_counter_32k_hwmod;
+extern struct omap_hwmod omap2xxx_rng_hwmod;
/* Common interface data across OMAP2xxx */
extern struct omap_hwmod_ocp_if omap2xxx_l3_main__l4_core;
@@ -102,6 +102,7 @@ extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_dispc;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_rfbi;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_venc;
+extern struct omap_hwmod_ocp_if omap2xxx_l4_core__rng;
/* Common IP block data */
extern struct omap_hwmod_dma_info omap2_uart1_sdma_reqs[];
--
To unsubscribe from this list: send the line "unsubscribe linux-omap" in
the body of a message to majordomo@vger.kernel.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply related [flat|nested] 11+ messages in thread
* [PATCH 2/5] hwrng: OMAP: store per-device data in per-device variables, not file statics
2012-08-27 23:36 [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Paul Walmsley
2012-08-27 23:36 ` [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data Paul Walmsley
@ 2012-08-27 23:36 ` Paul Walmsley
2012-08-27 23:36 ` [PATCH 3/5] hwrng: OMAP: convert to use runtime PM Paul Walmsley
` (3 subsequent siblings)
5 siblings, 0 replies; 11+ messages in thread
From: Paul Walmsley @ 2012-08-27 23:36 UTC (permalink / raw)
To: linux-omap, linux-arm-kernel; +Cc: Herbert Xu, Matt Mackall, linux-kernel
Encapsulate all of the RNG per-device state into a single per-device
structure record, as opposed to a set of per-driver file variables.
Signed-off-by: Paul Walmsley <paul@pwsan.com>
Cc: Matt Mackall <mpm@selenic.com>
Cc: Herbert Xu <herbert@gondor.apana.org.au>
---
drivers/char/hw_random/omap-rng.c | 115 +++++++++++++++++++++++++------------
1 file changed, 77 insertions(+), 38 deletions(-)
diff --git a/drivers/char/hw_random/omap-rng.c b/drivers/char/hw_random/omap-rng.c
index 4fbdceb..e0f0b98 100644
--- a/drivers/char/hw_random/omap-rng.c
+++ b/drivers/char/hw_random/omap-rng.c
@@ -23,6 +23,7 @@
#include <linux/platform_device.h>
#include <linux/hw_random.h>
#include <linux/delay.h>
+#include <linux/slab.h>
#include <asm/io.h>
@@ -46,26 +47,38 @@
#define RNG_SYSSTATUS 0x44 /* System status
[0] = RESETDONE */
-static void __iomem *rng_base;
-static struct clk *rng_ick;
-static struct platform_device *rng_dev;
+/**
+ * struct omap_rng_private_data - RNG IP block-specific data
+ * @base: virtual address of the beginning of the RNG IP block registers
+ * @clk: RNG clock
+ * @mem_res: struct resource * for the IP block registers physical memory
+ */
+struct omap_rng_private_data {
+ void __iomem *base;
+ struct clk *clk;
+ struct resource *mem_res;
+};
-static inline u32 omap_rng_read_reg(int reg)
+static inline u32 omap_rng_read_reg(struct omap_rng_private_data *priv, int reg)
{
- return __raw_readl(rng_base + reg);
+ return __raw_readl(priv->base + reg);
}
-static inline void omap_rng_write_reg(int reg, u32 val)
+static inline void omap_rng_write_reg(struct omap_rng_private_data *priv,
+ int reg, u32 val)
{
- __raw_writel(val, rng_base + reg);
+ __raw_writel(val, priv->base + reg);
}
static int omap_rng_data_present(struct hwrng *rng, int wait)
{
+ struct omap_rng_private_data *priv;
int data, i;
+ priv = (struct omap_rng_private_data *)rng->priv;
+
for (i = 0; i < 20; i++) {
- data = omap_rng_read_reg(RNG_STAT_REG) ? 0 : 1;
+ data = omap_rng_read_reg(priv, RNG_STAT_REG) ? 0 : 1;
if (data || !wait)
break;
/* RNG produces data fast enough (2+ MBit/sec, even
@@ -80,9 +93,13 @@ static int omap_rng_data_present(struct hwrng *rng, int wait)
static int omap_rng_data_read(struct hwrng *rng, u32 *data)
{
- *data = omap_rng_read_reg(RNG_OUT_REG);
+ struct omap_rng_private_data *priv;
+
+ priv = (struct omap_rng_private_data *)rng->priv;
+
+ *data = omap_rng_read_reg(priv, RNG_OUT_REG);
- return 4;
+ return sizeof(u32);
}
static struct hwrng omap_rng_ops = {
@@ -93,69 +110,85 @@ static struct hwrng omap_rng_ops = {
static int __devinit omap_rng_probe(struct platform_device *pdev)
{
- struct resource *res;
+ struct omap_rng_private_data *priv;
int ret;
- /*
- * A bit ugly, and it will never actually happen but there can
- * be only one RNG and this catches any bork
- */
- if (rng_dev)
- return -EBUSY;
+ priv = kzalloc(sizeof(struct omap_rng_private_data), GFP_KERNEL);
+ if (!priv) {
+ dev_err(&pdev->dev, "could not allocate memory\n");
+ return -ENOMEM;
+ };
+
+ omap_rng_ops.priv = (unsigned long)priv;
+ dev_set_drvdata(&pdev->dev, priv);
if (cpu_is_omap24xx()) {
- rng_ick = clk_get(&pdev->dev, "ick");
- if (IS_ERR(rng_ick)) {
+ priv->clk = clk_get(&pdev->dev, "ick");
+ if (IS_ERR(priv->clk)) {
dev_err(&pdev->dev, "Could not get rng_ick\n");
- ret = PTR_ERR(rng_ick);
+ ret = PTR_ERR(priv->clk);
return ret;
- } else
- clk_enable(rng_ick);
+ } else {
+ clk_enable(priv->clk);
+ }
}
- res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ priv->mem_res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (!priv->mem_res) {
+ ret = -ENOENT;
+ goto err_ioremap;
+ }
- rng_base = devm_request_and_ioremap(&pdev->dev, res);
- if (!rng_base) {
+ priv->base = devm_request_and_ioremap(&pdev->dev, priv->mem_res);
+ if (!priv->base) {
ret = -ENOMEM;
goto err_ioremap;
}
- dev_set_drvdata(&pdev->dev, res);
+ dev_set_drvdata(&pdev->dev, priv);
ret = hwrng_register(&omap_rng_ops);
if (ret)
goto err_register;
dev_info(&pdev->dev, "OMAP Random Number Generator ver. %02x\n",
- omap_rng_read_reg(RNG_REV_REG));
- omap_rng_write_reg(RNG_MASK_REG, 0x1);
+ omap_rng_read_reg(priv, RNG_REV_REG));
+
- rng_dev = pdev;
+ omap_rng_write_reg(priv, RNG_MASK_REG, 0x1);
return 0;
err_register:
- rng_base = NULL;
+ priv->base = NULL;
err_ioremap:
if (cpu_is_omap24xx()) {
- clk_disable(rng_ick);
- clk_put(rng_ick);
+ clk_disable(priv->clk);
+ clk_put(priv->clk);
}
+
+ kfree(priv);
+
return ret;
}
static int __exit omap_rng_remove(struct platform_device *pdev)
{
+ struct omap_rng_private_data *priv = dev_get_drvdata(&pdev->dev);
+
hwrng_unregister(&omap_rng_ops);
- omap_rng_write_reg(RNG_MASK_REG, 0x0);
+ omap_rng_write_reg(priv, RNG_MASK_REG, 0x0);
+
+ iounmap(priv->base);
if (cpu_is_omap24xx()) {
- clk_disable(rng_ick);
- clk_put(rng_ick);
+ clk_disable(priv->clk);
+ clk_put(priv->clk);
}
- rng_base = NULL;
+ release_mem_region(priv->mem_res->start, resource_size(priv->mem_res));
+
+ kfree(priv);
return 0;
}
@@ -164,13 +197,19 @@ static int __exit omap_rng_remove(struct platform_device *pdev)
static int omap_rng_suspend(struct device *dev)
{
- omap_rng_write_reg(RNG_MASK_REG, 0x0);
+ struct omap_rng_private_data *priv = dev_get_drvdata(dev);
+
+ omap_rng_write_reg(priv, RNG_MASK_REG, 0x0);
+
return 0;
}
static int omap_rng_resume(struct device *dev)
{
- omap_rng_write_reg(RNG_MASK_REG, 0x1);
+ struct omap_rng_private_data *priv = dev_get_drvdata(dev);
+
+ omap_rng_write_reg(priv, RNG_MASK_REG, 0x1);
+
return 0;
}
^ permalink raw reply related [flat|nested] 11+ messages in thread
* [PATCH 4/5] ARM: OMAP: split OMAP1, OMAP2+ RNG device registration
2012-08-27 23:36 [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Paul Walmsley
` (2 preceding siblings ...)
2012-08-27 23:36 ` [PATCH 3/5] hwrng: OMAP: convert to use runtime PM Paul Walmsley
@ 2012-08-27 23:36 ` Paul Walmsley
2012-08-27 23:36 ` [PATCH 5/5] hwrng: OMAP: remove SoC restrictions from driver registration Paul Walmsley
2012-08-30 20:27 ` [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Tony Lindgren
5 siblings, 0 replies; 11+ messages in thread
From: Paul Walmsley @ 2012-08-27 23:36 UTC (permalink / raw)
To: linux-omap, linux-arm-kernel
Move the OMAP1-specific RNG device creation off to mach-omap1/devices.c,
and create a omap_device-backed registration function for OMAP2+ devices
in mach-omap2/devices.c.
As a nice side-benefit, we can also get rid of
arch/arm/plat-omap/devices.c, thanks to some of the recent changes
from Tony.
One change from the previous behavior is that the RNG devices are now
registered unconditionally. This should allow the RNG drivers to be
loaded as modules, even if the original kernel was not built that way.
Signed-off-by: Paul Walmsley <paul@pwsan.com>
---
arch/arm/mach-omap1/devices.c | 25 +++++++++++
arch/arm/mach-omap2/devices.c | 18 ++++++++
arch/arm/plat-omap/Makefile | 3 -
arch/arm/plat-omap/devices.c | 92 -----------------------------------------
4 files changed, 44 insertions(+), 94 deletions(-)
delete mode 100644 arch/arm/plat-omap/devices.c
diff --git a/arch/arm/mach-omap1/devices.c b/arch/arm/mach-omap1/devices.c
index fa1fa4d..7f3d9d2 100644
--- a/arch/arm/mach-omap1/devices.c
+++ b/arch/arm/mach-omap1/devices.c
@@ -358,6 +358,30 @@ static inline void omap_init_uwire(void) {}
#endif
+#define OMAP1_RNG_BASE 0xfffe5000
+
+static struct resource omap1_rng_resources[] = {
+ {
+ .start = OMAP1_RNG_BASE,
+ .end = OMAP1_RNG_BASE + 0x4f,
+ .flags = IORESOURCE_MEM,
+ },
+};
+
+static struct platform_device omap1_rng_device = {
+ .name = "omap_rng",
+ .id = -1,
+ .num_resources = ARRAY_SIZE(omap1_rng_resources),
+ .resource = omap1_rng_resources,
+};
+
+static void omap1_init_rng(void)
+{
+ (void) platform_device_register(&omap1_rng_device);
+}
+
+/*-------------------------------------------------------------------------*/
+
/*
* This gets called after board-specific INIT_MACHINE, and initializes most
* on-chip peripherals accessible on this board (except for few like USB):
@@ -396,6 +420,7 @@ static int __init omap1_init_devices(void)
omap_init_spi100k();
omap_init_sti();
omap_init_uwire();
+ omap1_init_rng();
return 0;
}
diff --git a/arch/arm/mach-omap2/devices.c b/arch/arm/mach-omap2/devices.c
index c00c689..bc62f1e 100644
--- a/arch/arm/mach-omap2/devices.c
+++ b/arch/arm/mach-omap2/devices.c
@@ -464,6 +464,23 @@ static void omap_init_pmu(void)
platform_device_register(&omap_pmu_device);
}
+/**
+ * omap_init_rng - bind the RNG hwmod to the RNG omap_device
+ *
+ * Bind the RNG hwmod to the RNG omap_device. No return value.
+ */
+static void omap_init_rng(void)
+{
+ struct omap_hwmod *oh;
+ struct platform_device *pdev;
+
+ oh = omap_hwmod_lookup("rng");
+ if (!oh)
+ return;
+
+ pdev = omap_device_build("omap_rng", -1, oh, NULL, 0, NULL, 0, 0);
+ WARN(IS_ERR(pdev), "Can't build omap_device for omap_rng\n");
+}
#if defined(CONFIG_CRYPTO_DEV_OMAP_SHAM) || defined(CONFIG_CRYPTO_DEV_OMAP_SHAM_MODULE)
@@ -647,6 +664,7 @@ static int __init omap2_init_devices(void)
}
omap_init_pmu();
omap_init_sti();
+ omap_init_rng();
omap_init_sham();
omap_init_aes();
omap_init_vout();
diff --git a/arch/arm/plat-omap/Makefile b/arch/arm/plat-omap/Makefile
index 961bf85..a017e99 100644
--- a/arch/arm/plat-omap/Makefile
+++ b/arch/arm/plat-omap/Makefile
@@ -3,8 +3,7 @@
#
# Common support
-obj-y := common.o sram.o clock.o devices.o dma.o mux.o \
- fb.o counter_32k.o
+obj-y := common.o sram.o clock.o dma.o mux.o fb.o counter_32k.o
obj-m :=
obj-n :=
obj- :=
diff --git a/arch/arm/plat-omap/devices.c b/arch/arm/plat-omap/devices.c
deleted file mode 100644
index 1cba927..0000000
--- a/arch/arm/plat-omap/devices.c
+++ /dev/null
@@ -1,92 +0,0 @@
-/*
- * linux/arch/arm/plat-omap/devices.c
- *
- * Common platform device setup/initialization for OMAP1 and OMAP2
- *
- * This program is free software; you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation; either version 2 of the License, or
- * (at your option) any later version.
- */
-#include <linux/gpio.h>
-#include <linux/module.h>
-#include <linux/kernel.h>
-#include <linux/init.h>
-#include <linux/platform_device.h>
-#include <linux/io.h>
-#include <linux/slab.h>
-#include <linux/memblock.h>
-
-#include <mach/hardware.h>
-#include <asm/mach-types.h>
-#include <asm/mach/map.h>
-#include <asm/memblock.h>
-
-#include <plat/tc.h>
-#include <plat/board.h>
-#include <plat/mmc.h>
-#include <plat/menelaus.h>
-#include <plat/omap44xx.h>
-
-/*-------------------------------------------------------------------------*/
-
-#if defined(CONFIG_HW_RANDOM_OMAP) || defined(CONFIG_HW_RANDOM_OMAP_MODULE)
-
-#ifdef CONFIG_ARCH_OMAP2
-#define OMAP_RNG_BASE 0x480A0000
-#else
-#define OMAP_RNG_BASE 0xfffe5000
-#endif
-
-static struct resource rng_resources[] = {
- {
- .start = OMAP_RNG_BASE,
- .end = OMAP_RNG_BASE + 0x4f,
- .flags = IORESOURCE_MEM,
- },
-};
-
-static struct platform_device omap_rng_device = {
- .name = "omap_rng",
- .id = -1,
- .num_resources = ARRAY_SIZE(rng_resources),
- .resource = rng_resources,
-};
-
-static void omap_init_rng(void)
-{
- (void) platform_device_register(&omap_rng_device);
-}
-#else
-static inline void omap_init_rng(void) {}
-#endif
-
-/*
- * This gets called after board-specific INIT_MACHINE, and initializes most
- * on-chip peripherals accessible on this board (except for few like USB):
- *
- * (a) Does any "standard config" pin muxing needed. Board-specific
- * code will have muxed GPIO pins and done "nonstandard" setup;
- * that code could live in the boot loader.
- * (b) Populating board-specific platform_data with the data drivers
- * rely on to handle wiring variations.
- * (c) Creating platform devices as meaningful on this board and
- * with this kernel configuration.
- *
- * Claiming GPIOs, and setting their direction and initial values, is the
- * responsibility of the device drivers. So is responding to probe().
- *
- * Board-specific knowledge like creating devices or pin setup is to be
- * kept out of drivers as much as possible. In particular, pin setup
- * may be handled by the boot loader, and drivers should expect it will
- * normally have been done by the time they're probed.
- */
-static int __init omap_init_devices(void)
-{
- /* please keep these calls, and their implementations above,
- * in alphabetical order so they're easier to sort through.
- */
- omap_init_rng();
- return 0;
-}
-arch_initcall(omap_init_devices);
^ permalink raw reply related [flat|nested] 11+ messages in thread
* [PATCH 3/5] hwrng: OMAP: convert to use runtime PM
2012-08-27 23:36 [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Paul Walmsley
2012-08-27 23:36 ` [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data Paul Walmsley
2012-08-27 23:36 ` [PATCH 2/5] hwrng: OMAP: store per-device data in per-device variables, not file statics Paul Walmsley
@ 2012-08-27 23:36 ` Paul Walmsley
2012-08-27 23:36 ` [PATCH 4/5] ARM: OMAP: split OMAP1, OMAP2+ RNG device registration Paul Walmsley
` (2 subsequent siblings)
5 siblings, 0 replies; 11+ messages in thread
From: Paul Walmsley @ 2012-08-27 23:36 UTC (permalink / raw)
To: linux-omap, linux-arm-kernel; +Cc: Herbert Xu, Matt Mackall, linux-kernel
Convert the OMAP onboard hardware RNG driver to use runtime PM.
This allows us to remove some OMAP-specific cpu_is_omap*() calls from
the RNG driver.
Signed-off-by: Paul Walmsley <paul@pwsan.com>
Cc: Matt Mackall <mpm@selenic.com>
Cc: Herbert Xu <herbert@gondor.apana.org.au>
---
drivers/char/hw_random/omap-rng.c | 35 +++++++++--------------------------
1 file changed, 9 insertions(+), 26 deletions(-)
diff --git a/drivers/char/hw_random/omap-rng.c b/drivers/char/hw_random/omap-rng.c
index e0f0b98..748fcc8 100644
--- a/drivers/char/hw_random/omap-rng.c
+++ b/drivers/char/hw_random/omap-rng.c
@@ -18,12 +18,12 @@
#include <linux/module.h>
#include <linux/init.h>
#include <linux/random.h>
-#include <linux/clk.h>
#include <linux/err.h>
#include <linux/platform_device.h>
#include <linux/hw_random.h>
#include <linux/delay.h>
#include <linux/slab.h>
+#include <linux/pm_runtime.h>
#include <asm/io.h>
@@ -50,12 +50,10 @@
/**
* struct omap_rng_private_data - RNG IP block-specific data
* @base: virtual address of the beginning of the RNG IP block registers
- * @clk: RNG clock
* @mem_res: struct resource * for the IP block registers physical memory
*/
struct omap_rng_private_data {
void __iomem *base;
- struct clk *clk;
struct resource *mem_res;
};
@@ -122,17 +120,6 @@ static int __devinit omap_rng_probe(struct platform_device *pdev)
omap_rng_ops.priv = (unsigned long)priv;
dev_set_drvdata(&pdev->dev, priv);
- if (cpu_is_omap24xx()) {
- priv->clk = clk_get(&pdev->dev, "ick");
- if (IS_ERR(priv->clk)) {
- dev_err(&pdev->dev, "Could not get rng_ick\n");
- ret = PTR_ERR(priv->clk);
- return ret;
- } else {
- clk_enable(priv->clk);
- }
- }
-
priv->mem_res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
if (!priv->mem_res) {
ret = -ENOENT;
@@ -146,6 +133,9 @@ static int __devinit omap_rng_probe(struct platform_device *pdev)
}
dev_set_drvdata(&pdev->dev, priv);
+ pm_runtime_enable(&pdev->dev);
+ pm_runtime_get_sync(&pdev->dev);
+
ret = hwrng_register(&omap_rng_ops);
if (ret)
goto err_register;
@@ -153,19 +143,14 @@ static int __devinit omap_rng_probe(struct platform_device *pdev)
dev_info(&pdev->dev, "OMAP Random Number Generator ver. %02x\n",
omap_rng_read_reg(priv, RNG_REV_REG));
-
omap_rng_write_reg(priv, RNG_MASK_REG, 0x1);
return 0;
err_register:
priv->base = NULL;
+ pm_runtime_disable(&pdev->dev);
err_ioremap:
- if (cpu_is_omap24xx()) {
- clk_disable(priv->clk);
- clk_put(priv->clk);
- }
-
kfree(priv);
return ret;
@@ -179,12 +164,8 @@ static int __exit omap_rng_remove(struct platform_device *pdev)
omap_rng_write_reg(priv, RNG_MASK_REG, 0x0);
- iounmap(priv->base);
-
- if (cpu_is_omap24xx()) {
- clk_disable(priv->clk);
- clk_put(priv->clk);
- }
+ pm_runtime_put_sync(&pdev->dev);
+ pm_runtime_disable(&pdev->dev);
release_mem_region(priv->mem_res->start, resource_size(priv->mem_res));
@@ -200,6 +181,7 @@ static int omap_rng_suspend(struct device *dev)
struct omap_rng_private_data *priv = dev_get_drvdata(dev);
omap_rng_write_reg(priv, RNG_MASK_REG, 0x0);
+ pm_runtime_put_sync(dev);
return 0;
}
@@ -208,6 +190,7 @@ static int omap_rng_resume(struct device *dev)
{
struct omap_rng_private_data *priv = dev_get_drvdata(dev);
+ pm_runtime_get_sync(dev);
omap_rng_write_reg(priv, RNG_MASK_REG, 0x1);
return 0;
^ permalink raw reply related [flat|nested] 11+ messages in thread
* [PATCH 5/5] hwrng: OMAP: remove SoC restrictions from driver registration
2012-08-27 23:36 [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Paul Walmsley
` (3 preceding siblings ...)
2012-08-27 23:36 ` [PATCH 4/5] ARM: OMAP: split OMAP1, OMAP2+ RNG device registration Paul Walmsley
@ 2012-08-27 23:36 ` Paul Walmsley
2012-08-30 20:27 ` [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Tony Lindgren
5 siblings, 0 replies; 11+ messages in thread
From: Paul Walmsley @ 2012-08-27 23:36 UTC (permalink / raw)
To: linux-omap, linux-arm-kernel; +Cc: Herbert Xu, Matt Mackall, linux-kernel
Remove the SoC restriction code from the OMAP RNG driver. The
integration code in arch/arm/*omap* should handle this. The device
shouldn't be created if it doesn't exist on the currently-booted SoC.
This allows us to remove some OMAP-specific cpu_is_omap*() calls from
the driver. Also, if other OMAP chips have RNGs that can be used
by Linux, there will be no need to modify the driver.
Signed-off-by: Paul Walmsley <paul@pwsan.com>
Cc: Matt Mackall <mpm@selenic.com>
Cc: Herbert Xu <herbert@gondor.apana.org.au>
---
arch/arm/mach-omap1/devices.c | 3 +++
drivers/char/hw_random/omap-rng.c | 3 ---
2 files changed, 3 insertions(+), 3 deletions(-)
diff --git a/arch/arm/mach-omap1/devices.c b/arch/arm/mach-omap1/devices.c
index 7f3d9d2..aedd7a4 100644
--- a/arch/arm/mach-omap1/devices.c
+++ b/arch/arm/mach-omap1/devices.c
@@ -377,6 +377,9 @@ static struct platform_device omap1_rng_device = {
static void omap1_init_rng(void)
{
+ if (!cpu_is_omap16xx())
+ return;
+
(void) platform_device_register(&omap1_rng_device);
}
diff --git a/drivers/char/hw_random/omap-rng.c b/drivers/char/hw_random/omap-rng.c
index 748fcc8..a5effd8 100644
--- a/drivers/char/hw_random/omap-rng.c
+++ b/drivers/char/hw_random/omap-rng.c
@@ -220,9 +220,6 @@ static struct platform_driver omap_rng_driver = {
static int __init omap_rng_init(void)
{
- if (!cpu_is_omap16xx() && !cpu_is_omap24xx())
- return -ENODEV;
-
return platform_driver_register(&omap_rng_driver);
}
^ permalink raw reply related [flat|nested] 11+ messages in thread
* Re: [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM
2012-08-27 23:36 [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Paul Walmsley
` (4 preceding siblings ...)
2012-08-27 23:36 ` [PATCH 5/5] hwrng: OMAP: remove SoC restrictions from driver registration Paul Walmsley
@ 2012-08-30 20:27 ` Tony Lindgren
2012-08-30 20:29 ` Herbert Xu
5 siblings, 1 reply; 11+ messages in thread
From: Tony Lindgren @ 2012-08-30 20:27 UTC (permalink / raw)
To: Paul Walmsley; +Cc: linux-omap, Herbert Xu, linux-arm-kernel, Matt Mackall
* Paul Walmsley <paul@pwsan.com> [120827 16:39]:
> This series converts the OMAP hardware random number generator driver
> to use runtime PM. Hardware integration data is added for OMAP2xxx
> systems. I'm pretty sure this device is available on other OMAP chips
> too, but may require some experimentation with the integration details.
Good to hear. I believe that at some point this got moved to be
only accessible in the secure mode on later omaps?
> There are still a few rough edges with this series. Something is
> still not right with the reset behavior on OMAP2430, at least. But it
> would be good to get acks from the hwrng folks for the three patches that
> touch files in that directory. Will continue with the testing process
> here.
Yes Matt & Herbert, care to ack the drivers/char/hw_random related changes?
This series will conflict with the planned ARM common zImage changes
that we have planned so I'd like to merge them via the ARM soc tree.
Regards,
Tony
> - Paul
>
> ---
>
> Paul Walmsley (5):
> ARM: OMAP2/3: hwmod: add RNG integration data
> hwrng: OMAP: store per-device data in per-device variables, not file statics
> hwrng: OMAP: convert to use runtime PM
> ARM: OMAP: split OMAP1, OMAP2+ RNG device registration
> hwrng: OMAP: remove SoC restrictions from driver registration
>
>
> arch/arm/mach-omap1/devices.c | 28 +++++
> arch/arm/mach-omap2/devices.c | 18 +++
> arch/arm/mach-omap2/omap_hwmod_2420_data.c | 1
> arch/arm/mach-omap2/omap_hwmod_2430_data.c | 1
> .../mach-omap2/omap_hwmod_2xxx_interconnect_data.c | 17 +++
> arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c | 37 ++++++
> arch/arm/mach-omap2/omap_hwmod_common_data.h | 5 -
> arch/arm/plat-omap/Makefile | 3
> arch/arm/plat-omap/devices.c | 92 ---------------
> drivers/char/hw_random/omap-rng.c | 121 ++++++++++++--------
> 10 files changed, 176 insertions(+), 147 deletions(-)
> delete mode 100644 arch/arm/plat-omap/devices.c
>
> --
> To unsubscribe from this list: send the line "unsubscribe linux-omap" in
> the body of a message to majordomo@vger.kernel.org
> More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM
2012-08-30 20:27 ` [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Tony Lindgren
@ 2012-08-30 20:29 ` Herbert Xu
2012-08-30 20:57 ` Paul Walmsley
0 siblings, 1 reply; 11+ messages in thread
From: Herbert Xu @ 2012-08-30 20:29 UTC (permalink / raw)
To: Tony Lindgren; +Cc: Paul Walmsley, linux-omap, linux-arm-kernel, Matt Mackall
On Thu, Aug 30, 2012 at 01:27:08PM -0700, Tony Lindgren wrote:
> * Paul Walmsley <paul@pwsan.com> [120827 16:39]:
> > This series converts the OMAP hardware random number generator driver
> > to use runtime PM. Hardware integration data is added for OMAP2xxx
> > systems. I'm pretty sure this device is available on other OMAP chips
> > too, but may require some experimentation with the integration details.
>
> Good to hear. I believe that at some point this got moved to be
> only accessible in the secure mode on later omaps?
>
> > There are still a few rough edges with this series. Something is
> > still not right with the reset behavior on OMAP2430, at least. But it
> > would be good to get acks from the hwrng folks for the three patches that
> > touch files in that directory. Will continue with the testing process
> > here.
>
> Yes Matt & Herbert, care to ack the drivers/char/hw_random related changes?
Acked-by: Herbert Xu <herbert@gondor.apana.org.au>
> This series will conflict with the planned ARM common zImage changes
> that we have planned so I'd like to merge them via the ARM soc tree.
Thanks,
--
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] 11+ messages in thread
* Re: [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM
2012-08-30 20:29 ` Herbert Xu
@ 2012-08-30 20:57 ` Paul Walmsley
0 siblings, 0 replies; 11+ messages in thread
From: Paul Walmsley @ 2012-08-30 20:57 UTC (permalink / raw)
To: Herbert Xu; +Cc: Tony Lindgren, linux-omap, linux-arm-kernel, Matt Mackall
On Thu, 30 Aug 2012, Herbert Xu wrote:
> Acked-by: Herbert Xu <herbert@gondor.apana.org.au>
Great, thanks Herbert.
At some point in the next month or so, there should be similar series for
the OMAP crypto IP blocks too, which will need some acks - just as a
heads-up.
- Paul
^ permalink raw reply [flat|nested] 11+ messages in thread
* Re: [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data
2012-08-27 23:36 ` [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data Paul Walmsley
@ 2012-09-19 1:13 ` Paul Walmsley
2012-09-19 3:52 ` Paul Walmsley
0 siblings, 1 reply; 11+ messages in thread
From: Paul Walmsley @ 2012-09-19 1:13 UTC (permalink / raw)
To: linux-omap, linux-arm-kernel
[-- Attachment #1: Type: TEXT/PLAIN, Size: 7172 bytes --]
Hi
On Mon, 27 Aug 2012, Paul Walmsley wrote:
> Add integration data for the hardware random number generator IP block
> on some OMAP SoCs. This appears to be present on OMAP2xxx and OMAP3xxx
> SoCs, although it is not so easy to tell. It may also be present on
> other OMAP2+ SoCs.
>
> Signed-off-by: Paul Walmsley <paul@pwsan.com>
Found out what was causing the "omap_hwmod: rng: cannot be enabled for
reset (3)" messages; the CM code didn't recognize the CM_IDLEST4 register
as a valid idle status register, and returned an error. Here's an updated
version of the patch that fixes the problem.
- Paul
From: Paul Walmsley <paul@pwsan.com>
Date: Tue, 18 Sep 2012 17:38:26 -0600
Subject: [PATCH] ARM: OMAP2xxx: hwmod/CM: add RNG integration data
Add integration data for the hardware random number generator IP block
on some OMAP SoCs. This appears to be present on at least OMAP2xxx
and OMAP3xxx SoCs, although it is not so easy to tell. It may also be
present on other OMAP2+ SoCs.
Signed-off-by: Paul Walmsley <paul@pwsan.com>
---
arch/arm/mach-omap2/cm2xxx_3xxx.c | 2 +-
arch/arm/mach-omap2/cm2xxx_3xxx.h | 1 +
arch/arm/mach-omap2/omap_hwmod_2420_data.c | 1 +
arch/arm/mach-omap2/omap_hwmod_2430_data.c | 1 +
.../mach-omap2/omap_hwmod_2xxx_interconnect_data.c | 17 +++++++++
arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c | 37 ++++++++++++++++++++
arch/arm/mach-omap2/omap_hwmod_common_data.h | 5 +--
7 files changed, 61 insertions(+), 3 deletions(-)
diff --git a/arch/arm/mach-omap2/cm2xxx_3xxx.c b/arch/arm/mach-omap2/cm2xxx_3xxx.c
index 389f9f8..f01aa44 100644
--- a/arch/arm/mach-omap2/cm2xxx_3xxx.c
+++ b/arch/arm/mach-omap2/cm2xxx_3xxx.c
@@ -36,7 +36,7 @@
#define OMAP2XXX_APLL_AUTOIDLE_LOW_POWER_STOP 0x3
static const u8 cm_idlest_offs[] = {
- CM_IDLEST1, CM_IDLEST2, OMAP2430_CM_IDLEST3
+ CM_IDLEST1, CM_IDLEST2, OMAP2430_CM_IDLEST3, OMAP24XX_CM_IDLEST4
};
u32 omap2_cm_read_mod_reg(s16 module, u16 idx)
diff --git a/arch/arm/mach-omap2/cm2xxx_3xxx.h b/arch/arm/mach-omap2/cm2xxx_3xxx.h
index 088bbad..57b2f3c 100644
--- a/arch/arm/mach-omap2/cm2xxx_3xxx.h
+++ b/arch/arm/mach-omap2/cm2xxx_3xxx.h
@@ -71,6 +71,7 @@
#define OMAP24XX_CM_FCLKEN2 0x0004
#define OMAP24XX_CM_ICLKEN4 0x001c
#define OMAP24XX_CM_AUTOIDLE4 0x003c
+#define OMAP24XX_CM_IDLEST4 0x002c
#define OMAP2430_CM_IDLEST3 0x0028
diff --git a/arch/arm/mach-omap2/omap_hwmod_2420_data.c b/arch/arm/mach-omap2/omap_hwmod_2420_data.c
index 50cfab6..5a53287 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2420_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2420_data.c
@@ -587,6 +587,7 @@ static struct omap_hwmod_ocp_if *omap2420_hwmod_ocp_ifs[] __initdata = {
&omap2420_l4_core__mcbsp1,
&omap2420_l4_core__mcbsp2,
&omap2420_l4_core__msdi1,
+ &omap2xxx_l4_core__rng,
&omap2420_l4_core__hdq1w,
&omap2420_l4_wkup__counter_32k,
NULL,
diff --git a/arch/arm/mach-omap2/omap_hwmod_2430_data.c b/arch/arm/mach-omap2/omap_hwmod_2430_data.c
index 58b5bc1..256d8f6 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2430_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2430_data.c
@@ -947,6 +947,7 @@ static struct omap_hwmod_ocp_if *omap2430_hwmod_ocp_ifs[] __initdata = {
&omap2430_l4_core__mcbsp4,
&omap2430_l4_core__mcbsp5,
&omap2430_l4_core__hdq1w,
+ &omap2xxx_l4_core__rng,
&omap2430_l4_wkup__counter_32k,
NULL,
};
diff --git a/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c b/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
index 5178e40..14dc5ca 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
@@ -129,6 +129,15 @@ struct omap_hwmod_addr_space omap2xxx_mcbsp2_addrs[] = {
{ }
};
+static struct omap_hwmod_addr_space omap2_rng_addr_space[] = {
+ {
+ .pa_start = 0x480a0000,
+ .pa_end = 0x480a004f,
+ .flags = ADDR_TYPE_RT
+ },
+ { }
+};
+
/*
* Common interconnect data
*/
@@ -372,3 +381,11 @@ struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_venc = {
.user = OCP_USER_MPU | OCP_USER_SDMA,
};
+/* l4_core -> rng */
+struct omap_hwmod_ocp_if omap2xxx_l4_core__rng = {
+ .master = &omap2xxx_l4_core_hwmod,
+ .slave = &omap2xxx_rng_hwmod,
+ .clk = "l4_ck",
+ .addr = omap2_rng_addr_space,
+ .user = OCP_USER_MPU | OCP_USER_SDMA,
+};
diff --git a/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c b/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
index afad69c..06a37db 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
@@ -745,3 +745,40 @@ struct omap_hwmod omap2xxx_counter_32k_hwmod = {
},
.class = &omap2xxx_counter_hwmod_class,
};
+
+/* RNG */
+
+static struct omap_hwmod_class_sysconfig omap2_rng_sysc = {
+ .rev_offs = 0x3c,
+ .sysc_offs = 0x40,
+ .syss_offs = 0x44,
+ .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE |
+ SYSS_HAS_RESET_STATUS),
+ .sysc_fields = &omap_hwmod_sysc_type1,
+};
+
+static struct omap_hwmod_class omap2_rng_hwmod_class = {
+ .name = "rng",
+ .sysc = &omap2_rng_sysc,
+};
+
+static struct omap_hwmod_irq_info omap2_rng_mpu_irqs[] = {
+ { .irq = 52 },
+ { .irq = -1 }
+};
+
+struct omap_hwmod omap2xxx_rng_hwmod = {
+ .name = "rng",
+ .mpu_irqs = omap2_rng_mpu_irqs,
+ .main_clk = "l4_ck",
+ .prcm = {
+ .omap2 = {
+ .module_offs = CORE_MOD,
+ .prcm_reg_id = 4,
+ .module_bit = OMAP24XX_EN_RNG_SHIFT,
+ .idlest_reg_id = 4,
+ .idlest_idle_bit = OMAP24XX_ST_RNG_SHIFT,
+ },
+ },
+ .class = &omap2_rng_hwmod_class,
+};
diff --git a/arch/arm/mach-omap2/omap_hwmod_common_data.h b/arch/arm/mach-omap2/omap_hwmod_common_data.h
index e7e8eea..4363610 100644
--- a/arch/arm/mach-omap2/omap_hwmod_common_data.h
+++ b/arch/arm/mach-omap2/omap_hwmod_common_data.h
@@ -2,9 +2,8 @@
* omap_hwmod_common_data.h - OMAP hwmod common macros and declarations
*
* Copyright (C) 2010-2011 Nokia Corporation
+ * Copyright (C) 2010-2012 Texas Instruments, Inc.
* Paul Walmsley
- *
- * Copyright (C) 2010-2011 Texas Instruments, Inc.
* Benoît Cousson
*
* This program is free software; you can redistribute it and/or modify
@@ -76,6 +75,7 @@ extern struct omap_hwmod omap2xxx_gpio4_hwmod;
extern struct omap_hwmod omap2xxx_mcspi1_hwmod;
extern struct omap_hwmod omap2xxx_mcspi2_hwmod;
extern struct omap_hwmod omap2xxx_counter_32k_hwmod;
+extern struct omap_hwmod omap2xxx_rng_hwmod;
/* Common interface data across OMAP2xxx */
extern struct omap_hwmod_ocp_if omap2xxx_l3_main__l4_core;
@@ -102,6 +102,7 @@ extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_dispc;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_rfbi;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_venc;
+extern struct omap_hwmod_ocp_if omap2xxx_l4_core__rng;
/* Common IP block data */
extern struct omap_hwmod_dma_info omap2_uart1_sdma_reqs[];
--
1.7.10.4
^ permalink raw reply related [flat|nested] 11+ messages in thread
* Re: [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data
2012-09-19 1:13 ` Paul Walmsley
@ 2012-09-19 3:52 ` Paul Walmsley
0 siblings, 0 replies; 11+ messages in thread
From: Paul Walmsley @ 2012-09-19 3:52 UTC (permalink / raw)
To: linux-omap, linux-arm-kernel
[-- Attachment #1: Type: TEXT/PLAIN, Size: 7993 bytes --]
On Wed, 19 Sep 2012, Paul Walmsley wrote:
> On Mon, 27 Aug 2012, Paul Walmsley wrote:
>
> > Add integration data for the hardware random number generator IP block
> > on some OMAP SoCs. This appears to be present on OMAP2xxx and OMAP3xxx
> > SoCs, although it is not so easy to tell. It may also be present on
> > other OMAP2+ SoCs.
> >
> > Signed-off-by: Paul Walmsley <paul@pwsan.com>
>
> Found out what was causing the "omap_hwmod: rng: cannot be enabled for
> reset (3)" messages; the CM code didn't recognize the CM_IDLEST4 register
> as a valid idle status register, and returned an error. Here's an updated
> version of the patch that fixes the problem.
... and fixing that and the RNG interface clock ultimately causes
imprecise external aborts whenever the SYSSTATUS register is read during
initial OCP softreset. Tried a few different approaches to fixing this
without any luck; it wouldn't surprise me if the RNG needed a custom reset
function to enable its clocks internally first. For the time being, I've
just marked this HWMOD_INIT_NO_RESET in the data, with a big comment.
Updated patch below.
- Paul
From: Paul Walmsley <paul@pwsan.com>
Date: Tue, 18 Sep 2012 17:38:26 -0600
Subject: [PATCH] ARM: OMAP2xxx: hwmod/CM: add RNG integration data
Add integration data for the hardware random number generator IP block
on some OMAP SoCs. This appears to be present on at least OMAP2xxx
and OMAP3xxx SoCs, although it is not so easy to tell. It may also be
present on other OMAP2+ SoCs.
Signed-off-by: Paul Walmsley <paul@pwsan.com>
---
arch/arm/mach-omap2/cm2xxx_3xxx.c | 2 +-
arch/arm/mach-omap2/cm2xxx_3xxx.h | 1 +
arch/arm/mach-omap2/omap_hwmod_2420_data.c | 1 +
arch/arm/mach-omap2/omap_hwmod_2430_data.c | 1 +
.../mach-omap2/omap_hwmod_2xxx_interconnect_data.c | 17 ++++++++
arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c | 44 ++++++++++++++++++++
arch/arm/mach-omap2/omap_hwmod_common_data.h | 5 ++-
7 files changed, 68 insertions(+), 3 deletions(-)
diff --git a/arch/arm/mach-omap2/cm2xxx_3xxx.c b/arch/arm/mach-omap2/cm2xxx_3xxx.c
index 389f9f8..f01aa44 100644
--- a/arch/arm/mach-omap2/cm2xxx_3xxx.c
+++ b/arch/arm/mach-omap2/cm2xxx_3xxx.c
@@ -36,7 +36,7 @@
#define OMAP2XXX_APLL_AUTOIDLE_LOW_POWER_STOP 0x3
static const u8 cm_idlest_offs[] = {
- CM_IDLEST1, CM_IDLEST2, OMAP2430_CM_IDLEST3
+ CM_IDLEST1, CM_IDLEST2, OMAP2430_CM_IDLEST3, OMAP24XX_CM_IDLEST4
};
u32 omap2_cm_read_mod_reg(s16 module, u16 idx)
diff --git a/arch/arm/mach-omap2/cm2xxx_3xxx.h b/arch/arm/mach-omap2/cm2xxx_3xxx.h
index 088bbad..57b2f3c 100644
--- a/arch/arm/mach-omap2/cm2xxx_3xxx.h
+++ b/arch/arm/mach-omap2/cm2xxx_3xxx.h
@@ -71,6 +71,7 @@
#define OMAP24XX_CM_FCLKEN2 0x0004
#define OMAP24XX_CM_ICLKEN4 0x001c
#define OMAP24XX_CM_AUTOIDLE4 0x003c
+#define OMAP24XX_CM_IDLEST4 0x002c
#define OMAP2430_CM_IDLEST3 0x0028
diff --git a/arch/arm/mach-omap2/omap_hwmod_2420_data.c b/arch/arm/mach-omap2/omap_hwmod_2420_data.c
index 50cfab6..5a53287 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2420_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2420_data.c
@@ -587,6 +587,7 @@ static struct omap_hwmod_ocp_if *omap2420_hwmod_ocp_ifs[] __initdata = {
&omap2420_l4_core__mcbsp1,
&omap2420_l4_core__mcbsp2,
&omap2420_l4_core__msdi1,
+ &omap2xxx_l4_core__rng,
&omap2420_l4_core__hdq1w,
&omap2420_l4_wkup__counter_32k,
NULL,
diff --git a/arch/arm/mach-omap2/omap_hwmod_2430_data.c b/arch/arm/mach-omap2/omap_hwmod_2430_data.c
index 58b5bc1..256d8f6 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2430_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2430_data.c
@@ -947,6 +947,7 @@ static struct omap_hwmod_ocp_if *omap2430_hwmod_ocp_ifs[] __initdata = {
&omap2430_l4_core__mcbsp4,
&omap2430_l4_core__mcbsp5,
&omap2430_l4_core__hdq1w,
+ &omap2xxx_l4_core__rng,
&omap2430_l4_wkup__counter_32k,
NULL,
};
diff --git a/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c b/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
index 5178e40..c83d6c5 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2xxx_interconnect_data.c
@@ -129,6 +129,15 @@ struct omap_hwmod_addr_space omap2xxx_mcbsp2_addrs[] = {
{ }
};
+static struct omap_hwmod_addr_space omap2_rng_addr_space[] = {
+ {
+ .pa_start = 0x480a0000,
+ .pa_end = 0x480a004f,
+ .flags = ADDR_TYPE_RT
+ },
+ { }
+};
+
/*
* Common interconnect data
*/
@@ -372,3 +381,11 @@ struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_venc = {
.user = OCP_USER_MPU | OCP_USER_SDMA,
};
+/* l4_core -> rng */
+struct omap_hwmod_ocp_if omap2xxx_l4_core__rng = {
+ .master = &omap2xxx_l4_core_hwmod,
+ .slave = &omap2xxx_rng_hwmod,
+ .clk = "rng_ick",
+ .addr = omap2_rng_addr_space,
+ .user = OCP_USER_MPU | OCP_USER_SDMA,
+};
diff --git a/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c b/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
index afad69c..546cf57 100644
--- a/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
+++ b/arch/arm/mach-omap2/omap_hwmod_2xxx_ipblock_data.c
@@ -745,3 +745,47 @@ struct omap_hwmod omap2xxx_counter_32k_hwmod = {
},
.class = &omap2xxx_counter_hwmod_class,
};
+
+/* RNG */
+
+static struct omap_hwmod_class_sysconfig omap2_rng_sysc = {
+ .rev_offs = 0x3c,
+ .sysc_offs = 0x40,
+ .syss_offs = 0x44,
+ .sysc_flags = (SYSC_HAS_SOFTRESET | SYSC_HAS_AUTOIDLE |
+ SYSS_HAS_RESET_STATUS),
+ .sysc_fields = &omap_hwmod_sysc_type1,
+};
+
+static struct omap_hwmod_class omap2_rng_hwmod_class = {
+ .name = "rng",
+ .sysc = &omap2_rng_sysc,
+};
+
+static struct omap_hwmod_irq_info omap2_rng_mpu_irqs[] = {
+ { .irq = 52 },
+ { .irq = -1 }
+};
+
+struct omap_hwmod omap2xxx_rng_hwmod = {
+ .name = "rng",
+ .mpu_irqs = omap2_rng_mpu_irqs,
+ .main_clk = "l4_ck",
+ .prcm = {
+ .omap2 = {
+ .module_offs = CORE_MOD,
+ .prcm_reg_id = 4,
+ .module_bit = OMAP24XX_EN_RNG_SHIFT,
+ .idlest_reg_id = 4,
+ .idlest_idle_bit = OMAP24XX_ST_RNG_SHIFT,
+ },
+ },
+ /*
+ * XXX The first read from the SYSSTATUS register of the RNG
+ * after the SYSCONFIG SOFTRESET bit is set triggers an
+ * imprecise external abort. It's unclear why this happens.
+ * Until this is analyzed, skip the IP block reset.
+ */
+ .flags = HWMOD_INIT_NO_RESET,
+ .class = &omap2_rng_hwmod_class,
+};
diff --git a/arch/arm/mach-omap2/omap_hwmod_common_data.h b/arch/arm/mach-omap2/omap_hwmod_common_data.h
index e7e8eea..4363610 100644
--- a/arch/arm/mach-omap2/omap_hwmod_common_data.h
+++ b/arch/arm/mach-omap2/omap_hwmod_common_data.h
@@ -2,9 +2,8 @@
* omap_hwmod_common_data.h - OMAP hwmod common macros and declarations
*
* Copyright (C) 2010-2011 Nokia Corporation
+ * Copyright (C) 2010-2012 Texas Instruments, Inc.
* Paul Walmsley
- *
- * Copyright (C) 2010-2011 Texas Instruments, Inc.
* Benoît Cousson
*
* This program is free software; you can redistribute it and/or modify
@@ -76,6 +75,7 @@ extern struct omap_hwmod omap2xxx_gpio4_hwmod;
extern struct omap_hwmod omap2xxx_mcspi1_hwmod;
extern struct omap_hwmod omap2xxx_mcspi2_hwmod;
extern struct omap_hwmod omap2xxx_counter_32k_hwmod;
+extern struct omap_hwmod omap2xxx_rng_hwmod;
/* Common interface data across OMAP2xxx */
extern struct omap_hwmod_ocp_if omap2xxx_l3_main__l4_core;
@@ -102,6 +102,7 @@ extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_dispc;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_rfbi;
extern struct omap_hwmod_ocp_if omap2xxx_l4_core__dss_venc;
+extern struct omap_hwmod_ocp_if omap2xxx_l4_core__rng;
/* Common IP block data */
extern struct omap_hwmod_dma_info omap2_uart1_sdma_reqs[];
--
1.7.10.4
^ permalink raw reply related [flat|nested] 11+ messages in thread
end of thread, other threads:[~2012-09-19 3:52 UTC | newest]
Thread overview: 11+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2012-08-27 23:36 [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Paul Walmsley
2012-08-27 23:36 ` [PATCH 1/5] ARM: OMAP2/3: hwmod: add RNG integration data Paul Walmsley
2012-09-19 1:13 ` Paul Walmsley
2012-09-19 3:52 ` Paul Walmsley
2012-08-27 23:36 ` [PATCH 2/5] hwrng: OMAP: store per-device data in per-device variables, not file statics Paul Walmsley
2012-08-27 23:36 ` [PATCH 3/5] hwrng: OMAP: convert to use runtime PM Paul Walmsley
2012-08-27 23:36 ` [PATCH 4/5] ARM: OMAP: split OMAP1, OMAP2+ RNG device registration Paul Walmsley
2012-08-27 23:36 ` [PATCH 5/5] hwrng: OMAP: remove SoC restrictions from driver registration Paul Walmsley
2012-08-30 20:27 ` [PATCH 0/5] hwrng/ARM: OMAP: convert to use runtime PM Tony Lindgren
2012-08-30 20:29 ` Herbert Xu
2012-08-30 20:57 ` Paul Walmsley
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).