Merged in ziggurat29/arch/stm32l4_rng (pull request #59)

support RNG on STM32L4.  add support for SAI1PLL and SAI2PLL.  fix some errors in defines and configs.
This commit is contained in:
Gregory Nutt 2016-03-25 14:25:12 -06:00
commit b2205c7b66
7 changed files with 480 additions and 15 deletions

View File

@ -415,7 +415,7 @@ config STM32L4_DISABLE_IDLE_SLEEP_DURING_DEBUG
as the ST-LINK2 with OpenOCD, if the ARM is put to sleep via the WFI
instruction, the debugger will disconnect, terminating the debug session.
config STM32L4_CUSTOM_CLOCKCONFIG
config ARCH_BOARD_STM32L4_CUSTOM_CLOCKCONFIG
bool "Custom clock configuration"
default n
---help---

View File

@ -150,3 +150,6 @@ ifeq ($(CONFIG_DEBUG),y)
CHIP_CSRCS += stm32l4_dumpgpio.c
endif
ifeq ($(CONFIG_STM32L4_RNG),y)
CHIP_CSRCS += stm32l4_rng.c
endif

View File

@ -172,9 +172,10 @@
/* AHB2 Base Addresses **************************************************************/
#define STM32L4_AES_BASE 0x50060800
#define STM32L4_ADC_BASE 0x50060000
#define STM32L4_OTG_FS_BASE 0x50040000
#define STM32L4_RNG_BASE 0x50060800
#define STM32L4_AES_BASE 0x50060000
#define STM32L4_ADC_BASE 0x50040000
#define STM32L4_OTG_FS_BASE 0x50000000
#define STM32L4_GPIOH_BASE 0x50001c00
#define STM32L4_GPIOG_BASE 0x48001800
#define STM32L4_GPIOF_BASE 0x48001400

View File

@ -0,0 +1,77 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32l4_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_STM32L4_RNG_H
#define __ARCH_ARM_STC_STM32_CHIP_STM32L4_RNG_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include "chip.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define STM32L4_RNG_CR_OFFSET 0x0000 /* RNG Control Register */
#define STM32L4_RNG_SR_OFFSET 0x0004 /* RNG Status Register */
#define STM32L4_RNG_DR_OFFSET 0x0008 /* RNG Data Register */
/* Register Addresses ***************************************************************/
#define STM32L4_RNG_CR (STM32L4_RNG_BASE+STM32L4_RNG_CR_OFFSET)
#define STM32L4_RNG_SR (STM32L4_RNG_BASE+STM32L4_RNG_SR_OFFSET)
#define STM32L4_RNG_DR (STM32L4_RNG_BASE+STM32L4_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_STM32L4_RNG_H */

View File

@ -89,8 +89,8 @@
#define STM32L4_RCC_ICSCR (STM32L4_RCC_BASE+STM32L4_RCC_ICSCR_OFFSET)
#define STM32L4_RCC_CFGR (STM32L4_RCC_BASE+STM32L4_RCC_CFGR_OFFSET)
#define STM32L4_RCC_PLLCFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLCFG_OFFSET)
#define STM32L4_RCC_PLLSAI1CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI1CFGR_OFFSET)
#define STM32L4_RCC_PLLSAI2CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI2CFGR_OFFSET)
#define STM32L4_RCC_PLLSAI1CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI1CFG_OFFSET)
#define STM32L4_RCC_PLLSAI2CFG (STM32L4_RCC_BASE+STM32L4_RCC_PLLSAI2CFG_OFFSET)
#define STM32L4_RCC_CIER (STM32L4_RCC_BASE+STM32L4_RCC_CIER_OFFSET)
#define STM32L4_RCC_CIFR (STM32L4_RCC_BASE+STM32L4_RCC_CIFR_OFFSET)
#define STM32L4_RCC_CICR (STM32L4_RCC_BASE+STM32L4_RCC_CICR_OFFSET)
@ -465,7 +465,7 @@
#define RCC_AHB2ENR_OTGFSEN (1 << 12) /* Bit 12: USB OTG FS module enable */
#define RCC_AHB2ENR_ADCEN (1 << 13) /* Bit 13: ADC interface enable (common to all ADCs) */
#define RCC_AHB2ENR_AESEN (1 << 16) /* Bit 16: AES Cryptographic module enable */
#define RCC_AHB2ENR_RNGEN (1 << 18) /* Bit 6: Random number generator module enable */
#define RCC_AHB2ENR_RNGEN (1 << 18) /* Bit 18: Random number generator module enable */
/* AHB3 Peripheral Clock enable register */

View File

@ -0,0 +1,300 @@
/****************************************************************************
* arch/arm/src/stm32/stm32l4_rng.c
*
* Copyright (C) 2012 Max Holtzberg. All rights reserved.
* Author: Max Holtzberg <mh@uvc.de>
* mods for STL32L4 port by dev@ziggurat29.com
*
* 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 <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include "up_arch.h"
#include "chip/stm32l4_rng.h"
#include "up_internal.h"
#ifdef CONFIG_STM32L4_RNG
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int stm32l4_rnginitialize(void);
static int stm32l4_rnginterrupt(int irq, void *context);
static void stm32l4_rngenable(void);
static void stm32l4_rngdisable(void);
static ssize_t stm32l4_rngread(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 */
stm32l4_rngread, /* read */
0, /* write */
0, /* seek */
0 /* ioctl */
#ifndef CONFIG_DISABLE_POLL
, 0 /* poll */
#endif
};
/****************************************************************************
* Private functions
****************************************************************************/
static int stm32l4_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(STM32L4_IRQ_RNG, stm32l4_rnginterrupt))
{
/* We could not attach the ISR to the interrupt */
vdbg("Could not attach IRQ.\n");
return -EAGAIN;
}
/* Enable interrupts */
regval = getreg32(STM32L4_RNG_CR);
regval |= RNG_CR_IE;
putreg32(regval, STM32L4_RNG_CR);
up_enable_irq(STM32L4_IRQ_RNG);
return OK;
}
static void stm32l4_rngenable()
{
uint32_t regval;
g_rngdev.rd_first = true;
regval = getreg32(STM32L4_RNG_CR);
regval |= RNG_CR_RNGEN;
putreg32(regval, STM32L4_RNG_CR);
/* XXX see stm32l4_rngdisable(), below; if interrupts are disabled there,
then they should also be enabled here (also, they should not be enabled
in stm32l4_rnginitialize())
*/
}
static void stm32l4_rngdisable()
{
uint32_t regval;
regval = getreg32(STM32L4_RNG_CR);
regval &= ~RNG_CR_RNGEN;
putreg32(regval, STM32L4_RNG_CR);
/* XXX I believe it's appropriate to also disable the interrupt, and clear
any interrupt pending bit. This 'disable' is called from within the
interrupt handler when the buffer has been finally filled, but if there
is still another interrupt pending, then the handler will be entered one
last time, and attempt to touch some now-invalid objects
*/
}
static int stm32l4_rnginterrupt(int irq, void *context)
{
uint32_t rngsr;
uint32_t data;
rngsr = getreg32(STM32L4_RNG_SR);
if (rngsr & RNG_SR_CEIS) /* Check for clock error int stat */
{
/* clear it, we will try again. */
putreg32(rngsr & ~RNG_SR_CEIS, STM32L4_RNG_SR);
return OK;
}
if (rngsr & RNG_SR_SEIS) /* Check for seed error in int stat */
{
uint32_t crval;
/* clear seed error, then disable/enable the rng and try again. */
putreg32(rngsr & ~RNG_SR_SEIS, STM32L4_RNG_SR);
crval = getreg32(STM32L4_RNG_CR);
crval &= ~RNG_CR_RNGEN;
putreg32(crval, STM32L4_RNG_CR);
crval |= RNG_CR_RNGEN;
putreg32(crval, STM32L4_RNG_CR);
return OK;
}
if (!(rngsr & RNG_SR_DRDY)) /* Data ready must be set */
{
/* This random value is not valid, we will try again. */
return OK;
}
data = getreg32(STM32L4_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. */
stm32l4_rngdisable();
sem_post(&g_rngdev.rd_readsem);
}
return OK;
}
/****************************************************************************
* Name: stm32l4_rngread
****************************************************************************/
static ssize_t stm32l4_rngread(struct file *filep, char *buffer, size_t buflen)
{
if (sem_wait(&g_rngdev.rd_devsem) != OK)
{
return -errno;
}
else
{
/* We've got the device semaphore, proceed with reading */
/* Initialize the operation semaphore with 0 for blocking until
* the buffer is filled from interrupts.
*/
sem_init(&g_rngdev.rd_readsem, 0, 0);
g_rngdev.rd_buflen = buflen;
g_rngdev.rd_buf = buffer;
/* Enable RNG with interrupts */
stm32l4_rngenable();
/* Wait until the buffer is filled */
sem_wait(&g_rngdev.rd_readsem);
/* done with the operation semaphore */
sem_destroy(&g_rngdev.rd_readsem);
/* Free RNG via the device semaphore for next use */
sem_post(&g_rngdev.rd_devsem);
return buflen;
}
}
/****************************************************************************
* Public Functions
****************************************************************************/
void up_rnginitialize()
{
stm32l4_rnginitialize();
register_driver("/dev/random", &g_rngops, 0444, NULL);
}
#endif /* CONFIG_STM32L4_RNG */

View File

@ -413,25 +413,25 @@ static inline void rcc_enableapb1(void)
regval = getreg32(STM32L4_RCC_APB1ENR2);
#ifdef CONFIG_STM32L4_LPTIM1
/* OPAMP clock enable */
/* Low power timer 1 clock enable */
regval |= RCC_APB1ENR2_LPTIM1EN;
#endif
#ifdef CONFIG_STM32L4_LPUART1
/* OPAMP clock enable */
/* Low power uart clock enable */
regval |= RCC_APB1ENR2_LPUART1EN;
#endif
#ifdef CONFIG_STM32L4_SWPMI
/* OPAMP clock enable */
/* Single-wire protocol master clock enable */
regval |= RCC_APB1ENR2_SWPMI1EN;
#endif
#ifdef CONFIG_STM32L4_LPTIM2
/* OPAMP clock enable */
/* Low power timer 2 clock enable */
regval |= RCC_APB1ENR2_LPTIM2EN;
#endif
@ -575,7 +575,18 @@ static void stm32l4_stdclockconfig(void)
}
}
#else /* if STM32L4_BOARD_USEHSE */
#elif defined(STM32L4_BOARD_USEMSI)
/* Enable Internal Multi-Speed Clock (MSI) */
# error STM32L4_BOARD_USEMSI not yet implemented in arch/arm/src/stm32l4/stm32l4x6xx_rcc.c
/* setting MSIRANGE */
/* setting MSIPLLEN */
regval = getreg32(STM32L4_RCC_CR);
regval |= RCC_CR_MSION; /* Enable MSI */
putreg32(regval, STM32L4_RCC_CR);
#elif defined(STM32L4_BOARD_USEHSE)
/* Enable External High-Speed Clock (HSE) */
regval = getreg32(STM32L4_RCC_CR);
@ -595,6 +606,10 @@ static void stm32l4_stdclockconfig(void)
break;
}
}
#else
# error stm32l4_stdclockconfig(), must have one of STM32L4_BOARD_USEHSI, STM32L4_BOARD_USEMSI, STM32L4_BOARD_USEHSE defined
#endif
/* Check for a timeout. If this timeout occurs, then we are hosed. We
@ -671,6 +686,10 @@ static void stm32l4_stdclockconfig(void)
regval |= RCC_PLLCFG_PLLREN;
#endif
/* XXX The choice of clock source to PLL (all three) is independent
* of the sys clock source choice, review the STM32L4_BOARD_USEHSI
* name; probably split it into two, one for PLL source and one
* for sys clock source */
#ifdef STM32L4_BOARD_USEHSI
regval |= RCC_PLLCFG_PLLSRC_HSI;
#else /* if STM32L4_BOARD_USEHSE */
@ -693,11 +712,38 @@ static void stm32l4_stdclockconfig(void)
#ifdef CONFIG_STM32L4_SAI1PLL
/* Configure SAI1 PLL */
regval = getreg32(STM32L4_RCC_PLLSAI1CFG);
/* Set the PLL dividers and multipliers to configure the SAI1 PLL */
regval = (STM32L4_PLLSAI1CFG_PLLN | STM32L4_PLLSAI1CFG_PLLP
| STM32L4_PLLSAI1CFG_PLLQ | STM32L4_PLLSAI1CFG_PLLR);
#ifdef STM32L4_PLLSAI1CFG_PLLP_ENABLED
regval |= RCC_PLLSAI1CFG_PLLPEN;
#endif
#ifdef STM32L4_PLLSAI1CFG_PLLQ_ENABLED
regval |= RCC_PLLSAI1CFG_PLLQEN;
#endif
#ifdef STM32L4_PLLSAI1CFG_PLLR_ENABLED
regval |= RCC_PLLSAI1CFG_PLLREN;
#endif
putreg32(regval, STM32L4_RCC_PLLSAI1CFG);
/* Enable the SAI1 PLL */
#warning PLLSAI1 TODO
/* Wait until the PLL is ready */
regval = getreg32(STM32L4_RCC_CR);
regval |= RCC_CR_PLLSAI1ON;
putreg32(regval, STM32L4_RCC_CR);
/* Wait until the PLL is ready */
while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLSAI1RDY) == 0)
{
}
#endif
#ifdef CONFIG_STM32L4_SAI2PLL
@ -706,8 +752,32 @@ static void stm32l4_stdclockconfig(void)
regval = getreg32(STM32L4_RCC_PLLSAI2CFG);
/* Enable the SAI2 PLL */
#warning PLLSAI2 TODO
/* Set the PLL dividers and multipliers to configure the SAI2 PLL */
regval = (STM32L4_PLLSAI2CFG_PLLN | STM32L4_PLLSAI2CFG_PLLP
| STM32L4_PLLSAI2CFG_PLLR);
#ifdef STM32L4_PLLSAI2CFG_PLLP_ENABLED
regval |= RCC_PLLSAI2CFG_PLLPEN;
#endif
#ifdef STM32L4_PLLSAI2CFG_PLLR_ENABLED
regval |= RCC_PLLSAI2CFG_PLLREN;
#endif
putreg32(regval, STM32L4_RCC_PLLSAI2CFG);
/* Enable the SAI1 PLL */
regval = getreg32(STM32L4_RCC_CR);
regval |= RCC_CR_PLLSAI2ON;
putreg32(regval, STM32L4_RCC_CR);
/* Wait until the PLL is ready */
while ((getreg32(STM32L4_RCC_CR) & RCC_CR_PLLSAI2RDY) == 0)
{
}
#endif
/* Enable FLASH prefetch, instruction cache, data cache, and 5 wait states */
@ -747,6 +817,20 @@ static void stm32l4_stdclockconfig(void)
stm32l4_rcc_enablelse();
#endif
#if defined(STM32L4_USE_CLK48)
/*XXX sanity if sdmmc1 or usb or rng, then we need to set the clk48 source
* and then we can also do away with STM32L4_USE_CLK48, and give better
* warning messages */
/*XXX sanity if our STM32L4_CLK48_SEL is YYY then we need to have already
* enabled ZZZ */
regval = getreg32(STM32L4_RCC_CCIPR);
regval &= RCC_CCIPR_CLK48SEL_MASK;
regval |= STM32L4_CLK48_SEL;
putreg32(regval, STM32L4_RCC_CCIPR);
#endif
}
}
#endif