aboutsummaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-10-13 00:08:02 -0700
committerpx4dev <px4@purgatory.org>2012-10-13 00:08:02 -0700
commit0ccaa1330bf0bcb6fd7ab6b966470f8e2f6c4275 (patch)
treede4f04aac9a97274d706d564fc61e798ac1033ab /nuttx/arch
parentd62ec78ab835153ef3ba480a5a4110465ba34372 (diff)
parente4ccbe7508fd31b76790986fc654dc588efb9dfe (diff)
downloadpx4-firmware-0ccaa1330bf0bcb6fd7ab6b966470f8e2f6c4275.tar.gz
px4-firmware-0ccaa1330bf0bcb6fd7ab6b966470f8e2f6c4275.tar.bz2
px4-firmware-0ccaa1330bf0bcb6fd7ab6b966470f8e2f6c4275.zip
Merge branch 'master' of file:///Users/Shared/NuttX
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5231 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/armv7-m/nvic.h18
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_systemreset.c79
-rw-r--r--nuttx/arch/arm/src/common/up_initialize.c6
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h10
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig2
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs10
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_rng.h77
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_eth.c82
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_gpio.c1
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rng.c264
10 files changed, 543 insertions, 6 deletions
diff --git a/nuttx/arch/arm/src/armv7-m/nvic.h b/nuttx/arch/arm/src/armv7-m/nvic.h
index 1d30c5f7c..6bd842a76 100644
--- a/nuttx/arch/arm/src/armv7-m/nvic.h
+++ b/nuttx/arch/arm/src/armv7-m/nvic.h
@@ -175,7 +175,7 @@
#define NVIC_CPUID_BASE_OFFSET 0x0d00 /* CPUID base register */
#define NVIC_INTCTRL_OFFSET 0x0d04 /* Interrupt control state register */
#define NVIC_VECTAB_OFFSET 0x0d08 /* Vector table offset register */
-#define NVIC_AIRC_OFFSET 0x0d0c /* Application interrupt/reset contol registr */
+#define NVIC_AIRCR_OFFSET 0x0d0c /* Application interrupt/reset contol registr */
#define NVIC_SYSCON_OFFSET 0x0d10 /* System control register */
#define NVIC_CFGCON_OFFSET 0x0d14 /* Configuration control register */
#define NVIC_SYSH_PRIORITY_OFFSET(n) (0x0d14 + 4*((n) >> 2))
@@ -348,7 +348,7 @@
#define NVIC_CPUID_BASE (ARMV7M_NVIC_BASE + NVIC_CPUID_BASE_OFFSET)
#define NVIC_INTCTRL (ARMV7M_NVIC_BASE + NVIC_INTCTRL_OFFSET)
#define NVIC_VECTAB (ARMV7M_NVIC_BASE + NVIC_VECTAB_OFFSET)
-#define NVIC_AIRC (ARMV7M_NVIC_BASE + NVIC_AIRC_OFFSET)
+#define NVIC_AIRCR (ARMV7M_NVIC_BASE + NVIC_AIRCR_OFFSET)
#define NVIC_SYSCON (ARMV7M_NVIC_BASE + NVIC_SYSCON_OFFSET)
#define NVIC_CFGCON (ARMV7M_NVIC_BASE + NVIC_CFGCON_OFFSET)
#define NVIC_SYSH_PRIORITY(n) (ARMV7M_NVIC_BASE + NVIC_SYSH_PRIORITY_OFFSET(n))
@@ -500,6 +500,20 @@
#define NVIC_SYSHCON_BUSFAULTENA (1 << 17) /* Bit 17: BusFault enabled */
#define NVIC_SYSHCON_USGFAULTENA (1 << 18) /* Bit 18: UsageFault enabled */
+/* Application Interrupt and Reset Control Register (AIRCR) */
+
+#define NVIC_AIRCR_VECTRESET (1 << 0) /* Bit 0: VECTRESET */
+#define NVIC_AIRCR_VECTCLRACTIVE (1 << 1) /* Bit 1: Reserved for debug use */
+#define NVIC_AIRCR_SYSRESETREQ (1 << 2) /* Bit 2: System reset */
+ /* Bits 2-7: Reserved */
+#define NVIC_AIRCR_PRIGROUP_SHIFT (8) /* Bits 8-14: PRIGROUP */
+#define NVIC_AIRCR_PRIGROUP_MASK (7 << NVIC_AIRCR_PRIGROUP_SHIFT)
+#define NVIC_AIRCR_ENDIANNESS (1 << 15) /* Bit 15: 1=Big endian */
+#define NVIC_AIRCR_VECTKEY_SHIFT (16) /* Bits 16-31: VECTKEY */
+#define NVIC_AIRCR_VECTKEY_MASK (0xffff << NVIC_AIRCR_VECTKEY_SHIFT)
+#define NVIC_AIRCR_VECTKEYSTAT_SHIFT (16) /* Bits 16-31: VECTKEYSTAT */
+#define NVIC_AIRCR_VECTKEYSTAT_MASK (0xffff << NVIC_AIRCR_VECTKEYSTAT_SHIFT)
+
/* Debug Exception and Monitor Control Register (DEMCR) */
#define NVIC_DEMCR_VCCORERESET (1 << 0) /* Bit 0: Reset Vector Catch */
diff --git a/nuttx/arch/arm/src/armv7-m/up_systemreset.c b/nuttx/arch/arm/src/armv7-m/up_systemreset.c
new file mode 100644
index 000000000..0d7bd2736
--- /dev/null
+++ b/nuttx/arch/arm/src/armv7-m/up_systemreset.c
@@ -0,0 +1,79 @@
+/****************************************************************************
+ * arch/arm/src/armv7-m/up_systemreset.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Darcy Gong
+ *
+ * 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 <nuttx/config.h>
+
+#include <stdint.h>
+
+#include "up_arch.h"
+#include "nvic.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+ /****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public functions
+ ****************************************************************************/
+
+void up_systemreset(void)
+{
+ uint32_t regval;
+
+ /* Set up for the system reset, retaining the priority group from the
+ * the AIRCR register.
+ */
+
+ regval = getreg32(NVIC_AIRCR) & NVIC_AIRCR_PRIGROUP_MASK;
+ regval |= ((0x5fa << NVIC_AIRCR_VECTKEY_SHIFT) | NVIC_AIRCR_SYSRESETREQ);
+ putreg32(regval, NVIC_AIRCR);
+
+ /* Ensure completion of memory accesses */
+
+ __asm volatile ("dsb");
+
+ /* Wait for the reset */
+
+ for (;;);
+}
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 9f20775c0..0d3c5b1f2 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -241,6 +241,10 @@ extern void up_pminitialize(void);
# define up_pminitialize()
#endif
+#if defined(CONFIG_ARCH_CORTEXM3) || defined(CONFIG_ARCH_CORTEXM4)
+extern void up_systemreset(void) noreturn_function;
+#endif
+
/* Interrupt handling *******************************************************/
extern void up_irqinitialize(void);
@@ -369,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 8d93fb104..2f9100236 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -269,6 +269,7 @@ config STM32_ETHMAC
bool "Ethernet MAC"
default n
depends on STM32_CONNECTIVITYLINE || STM32_STM32F20XX || STM32_STM32F40XX
+ select ARCH_HAVE_PHY
config STM32_FSMC
bool "FSMC"
@@ -319,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 32e84a78a..54067a168 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -45,8 +45,8 @@ CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \
up_initialize.c up_initialstate.c up_interruptcontext.c \
up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
up_releasepending.c up_releasestack.c up_reprioritizertr.c \
- up_schedulesigaction.c up_sigdeliver.c up_unblocktask.c \
- up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \
+ up_schedulesigaction.c up_sigdeliver.c up_systemreset.c \
+ up_unblocktask.c up_usestack.c up_doirq.c up_hardfault.c up_svcall.c \
up_stackcheck.c
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
@@ -83,7 +83,7 @@ endif
ifeq ($(CONFIG_USBHOST),y)
ifeq ($(CONFIG_STM32_OTGFS),y)
-CMN_CSRCS += stm32_otgfshost.c
+CMN_CSRCS += stm32_otgfshost.c
endif
endif
@@ -124,6 +124,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 <mh@uvc.de>
+ *
+ * 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 <nuttx/config.h>
+#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_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c
index 2e892c9e5..3054142ce 100644
--- a/nuttx/arch/arm/src/stm32/stm32_eth.c
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.c
@@ -664,6 +664,9 @@ static void stm32_rxdescinit(FAR struct stm32_ethmac_s *priv);
static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value);
static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value);
+#ifdef CONFIG_PHY_DM9161
+static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv);
+#endif
static int stm32_phyinit(FAR struct stm32_ethmac_s *priv);
/* MAC/DMA Initialization */
@@ -1653,6 +1656,7 @@ static void stm32_receive(FAR struct stm32_ethmac_s *priv)
stm32_freebuffer(priv, dev->d_buf);
dev->d_buf = NULL;
+ dev->d_len = 0;
}
}
}
@@ -1953,7 +1957,7 @@ static void stm32_polltimer(int argc, uint32_t arg, ...)
/* Check if the next TX descriptor is owned by the Ethernet DMA or CPU. We
* cannot perform the timer poll if we are unable to accept another packet
* for transmission. Hmmm.. might be bug here. Does this mean if there is
- * a transmit in progress, we will missing TCP time state updates?
+ * a transmit in progress, we will miss TCP time state updates?
*
* In a race condition, ETH_TDES0_OWN may be cleared BUT still not available
* because stm32_freeframe() has not yet run. If stm32_freeframe() has run,
@@ -2480,6 +2484,72 @@ static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t val
}
/****************************************************************************
+ * Function: stm32_dm9161
+ *
+ * Description:
+ * Special workaround for the Davicom DM9161 PHY is required. On power,
+ * up, the PHY is not usually configured correctly but will work after
+ * a powered-up reset. This is really a workaround for some more
+ * fundamental issue with the PHY clocking initialization, but the
+ * root cause has not been studied (nor will it be with this workaround).
+ *
+ * Parameters:
+ * priv - A reference to the private driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PHY_DM9161
+static inline int stm32_dm9161(FAR struct stm32_ethmac_s *priv)
+{
+ uint16_t phyval;
+ int ret;
+
+ /* Read the PHYID1 register; A failure to read the PHY ID is one
+ * indication that check if the DM9161 PHY CHIP is not ready.
+ */
+
+ ret = stm32_phyread(CONFIG_STM32_PHYADDR, MII_PHYID1, &phyval);
+ if (ret < 0)
+ {
+ ndbg("Failed to read the PHY ID1: %d\n", ret);
+ return ret;
+ }
+
+ /* If we failed to read the PHY ID1 register, the reset the MCU to recover */
+
+ else if (phyval == 0xffff)
+ {
+ up_systemreset();
+ }
+
+ nvdbg("PHY ID1: 0x%04X\n", phyval);
+
+ /* Now check the "DAVICOM Specified Configuration Register (DSCR)", Register 16 */
+
+ ret = stm32_phyread(CONFIG_STM32_PHYADDR, 16, &phyval);
+ if (ret < 0)
+ {
+ ndbg("Failed to read the PHY Register 0x10: %d\n", ret);
+ return ret;
+ }
+
+ /* Bit 8 of the DSCR register is zero, the the DM9161 has not selected RMII.
+ * If RMII is not selected, then reset the MCU to recover.
+ */
+
+ else if ((phyval & (1 << 8)) == 0)
+ {
+ up_systemreset();
+ }
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
* Function: stm32_phyinit
*
* Description:
@@ -2524,6 +2594,16 @@ static int stm32_phyinit(FAR struct stm32_ethmac_s *priv)
}
up_mdelay(PHY_RESET_DELAY);
+ /* Special workaround for the Davicom DM9161 PHY is required. */
+
+#ifdef CONFIG_PHY_DM9161
+ ret = stm32_dm9161(priv);
+ if (ret < 0)
+ {
+ return ret;
+ }
+#endif
+
/* Perform auto-negotion if so configured */
#ifdef CONFIG_STM32_AUTONEG
diff --git a/nuttx/arch/arm/src/stm32/stm32_gpio.c b/nuttx/arch/arm/src/stm32/stm32_gpio.c
index 4703e8208..1dedd7ce7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_gpio.c
+++ b/nuttx/arch/arm/src/stm32/stm32_gpio.c
@@ -128,6 +128,7 @@ static inline void stm32_gpioremap(void)
val |= AFIO_MAPR_SPI1_REMAP;
#endif
#ifdef CONFIG_STM32_SPI3_REMAP
+ val |= AFIO_MAPR_SPI3_REMAP;
#endif
#ifdef CONFIG_STM32_I2C1_REMAP
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 <mh@uvc.de>
+ *
+ * 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 <stdint.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#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);
+}