From 96a334a758bbdc466ba8ae0cb20f2f79958623ec Mon Sep 17 00:00:00 2001 From: patacongo Date: Sat, 29 Sep 2012 20:34:25 +0000 Subject: Implementation of /dev/random using the STM32 Random Number Generator (RNG) git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5207 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 4 + nuttx/arch/arm/src/common/up_initialize.c | 6 + nuttx/arch/arm/src/common/up_internal.h | 6 + nuttx/arch/arm/src/stm32/Kconfig | 1 + nuttx/arch/arm/src/stm32/Make.defs | 6 +- nuttx/arch/arm/src/stm32/chip/stm32_rng.h | 77 +++++++++ nuttx/arch/arm/src/stm32/stm32_rng.c | 264 ++++++++++++++++++++++++++++++ nuttx/configs/stm3240g-eval/README.txt | 11 +- nuttx/configs/stm3240g-eval/nsh/defconfig | 4 +- nuttx/configs/stm3240g-eval/src/Makefile | 4 +- nuttx/drivers/Kconfig | 8 + 11 files changed, 385 insertions(+), 6 deletions(-) create mode 100644 nuttx/arch/arm/src/stm32/chip/stm32_rng.h create mode 100644 nuttx/arch/arm/src/stm32/stm32_rng.c (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index ef9e77132..55a06aeec 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3454,3 +3454,7 @@ going outside of local network. Submitted by Darcy Gong 6.23 2012-09-29 Gregory Nutt + + * arch/arm/src/stm32/stm32_rng.c, chip/stm32_rng.h, and other files: + Implementation of /dev/random using the STM32 Random Number + Generator (RNG). diff --git a/nuttx/arch/arm/src/common/up_initialize.c b/nuttx/arch/arm/src/common/up_initialize.c index 094835c29..80f9b1193 100644 --- a/nuttx/arch/arm/src/common/up_initialize.c +++ b/nuttx/arch/arm/src/common/up_initialize.c @@ -171,6 +171,12 @@ void up_initialize(void) ramlog_consoleinit(); #endif + /* Initialize the Random Number Generator (RNG) */ + +#ifdef CONFIG_DEV_RANDOM + up_rnginitialize(); +#endif + /* Initialize the system logging device */ #ifdef CONFIG_SYSLOG_CHAR diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h index 42142c5e8..0d3c5b1f2 100644 --- a/nuttx/arch/arm/src/common/up_internal.h +++ b/nuttx/arch/arm/src/common/up_internal.h @@ -373,6 +373,12 @@ extern void up_usbuninitialize(void); # define up_usbuninitialize() #endif +/* Random Number Generator (RNG) ********************************************/ + +#ifdef CONFIG_DEV_RANDOM +extern void up_rnginitialize(void); +#endif + /**************************************************************************** * Name: up_check_stack * diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig index fe89119a4..2f9100236 100644 --- a/nuttx/arch/arm/src/stm32/Kconfig +++ b/nuttx/arch/arm/src/stm32/Kconfig @@ -320,6 +320,7 @@ config STM32_RNG bool "RNG" default n depends on STM32_STM32F20XX || STM32_STM32F40XX + select ARCH_HAVE_RNG config STM32_SDIO bool "SDIO" diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs index e52962977..ef14b48c1 100644 --- a/nuttx/arch/arm/src/stm32/Make.defs +++ b/nuttx/arch/arm/src/stm32/Make.defs @@ -78,7 +78,7 @@ endif ifeq ($(CONFIG_USBHOST),y) ifeq ($(CONFIG_STM32_OTGFS),y) -CMN_CSRCS += stm32_otgfshost.c +CMN_CSRCS += stm32_otgfshost.c endif endif @@ -119,6 +119,10 @@ ifeq ($(CONFIG_DAC),y) CHIP_CSRCS += stm32_dac.c endif +ifeq ($(CONFIG_DEV_RANDOM),y) +CHIP_CSRCS += stm32_rng.c +endif + ifeq ($(CONFIG_PWM),y) CHIP_CSRCS += stm32_pwm.c endif diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_rng.h b/nuttx/arch/arm/src/stm32/chip/stm32_rng.h new file mode 100644 index 000000000..5e31d5817 --- /dev/null +++ b/nuttx/arch/arm/src/stm32/chip/stm32_rng.h @@ -0,0 +1,77 @@ +/************************************************************************************ + * arch/arm/src/stm32/chip/stm32_rng.h + * + * Copyright (C) 2012 Max Holtzberg. All rights reserved. + * Author: Max Holtzberg + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_STC_STM32_CHIP_STM32_RNG_H +#define __ARCH_ARM_STC_STM32_CHIP_STM32_RNG_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "chip.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* Register Offsets *****************************************************************/ + +#define STM32_RNG_CR_OFFSET 0x0000 /* RNG Control Register */ +#define STM32_RNG_SR_OFFSET 0x0004 /* RNG Status Register */ +#define STM32_RNG_DR_OFFSET 0x0008 /* RNG Data Register */ + +/* Register Addresses ***************************************************************/ + +#define STM32_RNG_CR (STM32_RNG_BASE+STM32_RNG_CR_OFFSET) +#define STM32_RNG_SR (STM32_RNG_BASE+STM32_RNG_SR_OFFSET) +#define STM32_RNG_DR (STM32_RNG_BASE+STM32_RNG_DR_OFFSET) + +/* Register Bitfield Definitions ****************************************************/ + +/* RNG Control Register */ + +#define RNG_CR_RNGEN (1 << 2) /* Bit 2: RNG enable */ +#define RNG_CR_IE (1 << 3) /* Bit 3: Interrupt enable */ + +/* RNG Status Register */ + +#define RNG_SR_DRDY (1 << 0) /* Bit 0: Data ready */ +#define RNG_SR_CECS (1 << 1) /* Bit 1: Clock error current status */ +#define RNG_SR_SECS (1 << 2) /* Bit 2: Seed error current status */ +#define RNG_SR_CEIS (1 << 5) /* Bit 5: Clock error interrupt status */ +#define RNG_SR_SEIS (1 << 6) /* Bit 6: Seed error interrupt status */ + +#endif /* __ARCH_ARM_STC_STM32_CHIP_STM32_RNG_H */ diff --git a/nuttx/arch/arm/src/stm32/stm32_rng.c b/nuttx/arch/arm/src/stm32/stm32_rng.c new file mode 100644 index 000000000..38e8108fe --- /dev/null +++ b/nuttx/arch/arm/src/stm32/stm32_rng.c @@ -0,0 +1,264 @@ +/**************************************************************************** + * arch/arm/src/stm32/stm32_rng.c + * + * Copyright (C) 2012 Max Holtzberg. All rights reserved. + * Author: Max Holtzberg + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include +#include + +#include +#include + +#include "up_arch.h" +#include "chip/stm32_rng.h" +#include "up_internal.h" + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int stm32_rnginitialize(void); +static int stm32_interrupt(int irq, void *context); +static void stm32_enable(void); +static void stm32_disable(void); +static ssize_t stm32_read(struct file *filep, char *buffer, size_t); + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct rng_dev_s +{ + sem_t rd_devsem; /* Threads can only exclusively access the RNG */ + sem_t rd_readsem; /* To block until the buffer is filled */ + char *rd_buf; + size_t rd_buflen; + uint32_t rd_lastval; + bool rd_first; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct rng_dev_s g_rngdev; + +static const struct file_operations g_rngops = +{ + 0, /* open */ + 0, /* close */ + stm32_read, /* read */ + 0, /* write */ + 0, /* seek */ + 0 /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + ,0 /* poll */ +#endif +}; + +/**************************************************************************** + * Private functions + ****************************************************************************/ + +static int stm32_rnginitialize() +{ + uint32_t regval; + + vdbg("Initializing RNG\n"); + + memset(&g_rngdev, 0, sizeof(struct rng_dev_s)); + + sem_init(&g_rngdev.rd_devsem, 0, 1); + + if (irq_attach(STM32_IRQ_RNG, stm32_interrupt)) + { + /* We could not attach the ISR to the interrupt */ + + vdbg("Could not attach IRQ.\n"); + + return -EAGAIN; + } + + /* Enable interrupts */ + + regval = getreg32(STM32_RNG_CR); + regval |= RNG_CR_IE; + putreg32(regval, STM32_RNG_CR); + + up_enable_irq(STM32_IRQ_RNG); + + return OK; +} + +static void stm32_enable() +{ + uint32_t regval; + + g_rngdev.rd_first = true; + + regval = getreg32(STM32_RNG_CR); + regval |= RNG_CR_RNGEN; + putreg32(regval, STM32_RNG_CR); +} + +static void stm32_disable() +{ + uint32_t regval; + regval = getreg32(STM32_RNG_CR); + regval &= ~RNG_CR_RNGEN; + putreg32(regval, STM32_RNG_CR); +} + +static int stm32_interrupt(int irq, void *context) +{ + uint32_t rngsr; + uint32_t data; + + rngsr = getreg32(STM32_RNG_SR); + + if ((rngsr & (RNG_SR_SEIS | RNG_SR_CEIS)) /* Check for error bits */ + || !(rngsr & RNG_SR_DRDY)) /* Data ready must be set */ + { + /* This random value is not valid, we will try again. */ + + return OK; + } + + data = getreg32(STM32_RNG_DR); + + /* As required by the FIPS PUB (Federal Information Processing Standard + * Publication) 140-2, the first random number generated after setting the + * RNGEN bit should not be used, but saved for comparison with the next + * generated random number. Each subsequent generated random number has to be + * compared with the previously generated number. The test fails if any two + * compared numbers are equal (continuous random number generator test). + */ + + if (g_rngdev.rd_first) + { + g_rngdev.rd_first = false; + g_rngdev.rd_lastval = data; + return OK; + } + + if (g_rngdev.rd_lastval == data) + { + /* Two subsequent same numbers, we will try again. */ + + return OK; + } + + /* If we get here, the random number is valid. */ + + g_rngdev.rd_lastval = data; + + if (g_rngdev.rd_buflen >= 4) + { + g_rngdev.rd_buflen -= 4; + *(uint32_t*)&g_rngdev.rd_buf[g_rngdev.rd_buflen] = data; + } + else + { + while (g_rngdev.rd_buflen > 0) + { + g_rngdev.rd_buf[--g_rngdev.rd_buflen] = (char)data; + data >>= 8; + } + } + + if (g_rngdev.rd_buflen == 0) + { + /* Buffer filled, stop further interrupts. */ + + stm32_disable(); + sem_post(&g_rngdev.rd_readsem); + } + + return OK; +} + +/**************************************************************************** + * Name: stm32_read + ****************************************************************************/ + +static ssize_t stm32_read(struct file *filep, char *buffer, size_t buflen) +{ + if (sem_wait(&g_rngdev.rd_devsem) != OK) + { + return -errno; + } + else + { + /* We've got the semaphore. */ + + /* Initialize semaphore with 0 for blocking until the buffer is filled from + * interrupts. + */ + + sem_init(&g_rngdev.rd_readsem, 0, 1); + + g_rngdev.rd_buflen = buflen; + g_rngdev.rd_buf = buffer; + + /* Enable RNG with interrupts */ + + stm32_enable(); + + /* Wait until the buffer is filled */ + + sem_wait(&g_rngdev.rd_readsem); + + /* Free RNG for next use */ + + sem_post(&g_rngdev.rd_devsem); + + return buflen; + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +void up_rnginitialize() +{ + stm32_rnginitialize(); + register_driver("/dev/random", &g_rngops, 0444, NULL); +} diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index df98f087d..b536097a8 100644 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -1110,7 +1110,16 @@ Where is one of the following: nsh> umount /mnt/stuff - 11. This configuration requires that jumper JP22 be set to enable RS-232 + 11. By default, this configuration supports /dev/random using the STM32's + RNG hardware. This can be disabled as follows: + + -CONFIG_STM32_RNG=y + +CONFIG_STM32_RNG=n + + -CONFIG_DEV_RANDOM=y + +CONFIG_DEV_RANDOM=n + + 12. This configuration requires that jumper JP22 be set to enable RS-232 operation. nsh2: diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig index 80f5ec167..653538b45 100644 --- a/nuttx/configs/stm3240g-eval/nsh/defconfig +++ b/nuttx/configs/stm3240g-eval/nsh/defconfig @@ -69,7 +69,6 @@ CONFIG_STM32_BUILDROOT=n # # JTAG Enable settings (by default JTAG-DP and SW-DP are disabled): # -CONFIG_STM32_DFU=y CONFIG_STM32_JTAG_FULL_ENABLE=y CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n CONFIG_STM32_JTAG_SW_ENABLE=n @@ -100,7 +99,7 @@ CONFIG_STM32_OTGHS=n CONFIG_STM32_DCMI=n CONFIG_STM32_CRYP=n CONFIG_STM32_HASH=n -CONFIG_STM32_RNG=n +CONFIG_STM32_RNG=y CONFIG_STM32_OTGFS=n # AHB3: CONFIG_STM32_FSMC=n @@ -306,6 +305,7 @@ CONFIG_SCHED_WORKSTACKSIZE=2048 CONFIG_SIG_SIGWORK=4 CONFIG_SCHED_WAITPID=y CONFIG_SCHED_ATEXIT=n +CONFIG_DEV_RANDOM=y # # System Logging diff --git a/nuttx/configs/stm3240g-eval/src/Makefile b/nuttx/configs/stm3240g-eval/src/Makefile index 80225ea1f..ffcf719ab 100644 --- a/nuttx/configs/stm3240g-eval/src/Makefile +++ b/nuttx/configs/stm3240g-eval/src/Makefile @@ -100,8 +100,8 @@ OBJS = $(AOBJS) $(COBJS) ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src ifeq ($(WINTOOL),y) CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ - -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" + -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \ + -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}" else CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m endif diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig index ea218a592..1d263ec14 100644 --- a/nuttx/drivers/Kconfig +++ b/nuttx/drivers/Kconfig @@ -11,6 +11,14 @@ config DEV_ZERO bool "Enable /dev/zero" default n +config ARCH_HAVE_RNG + bool + +config DEV_RANDOM + bool "Enable /dev/random" + default n + depends on ARCH_HAVE_RNG + config LOOP bool "Enable loop device" default n -- cgit v1.2.3