You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@mynewt.apache.org by ut...@apache.org on 2019/12/05 09:10:48 UTC

[mynewt-core] 05/06: mcu: stm32l1: update to syscfg based clock system

This is an automated email from the ASF dual-hosted git repository.

utzig pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/mynewt-core.git

commit f525514fed3fb829877311dc122bedfb96fb4211
Author: Fabio Utzig <ut...@apache.org>
AuthorDate: Wed Dec 4 09:19:41 2019 -0300

    mcu: stm32l1: update to syscfg based clock system
---
 .../include/bsp/stm32l1xx_hal_conf.h               |  52 +--
 hw/bsp/stm32l152discovery/src/hal_bsp.c            |  42 ---
 hw/bsp/stm32l152discovery/src/system_stm32l1xx.c   | 413 ---------------------
 hw/bsp/stm32l152discovery/syscfg.yml               |  18 +
 hw/mcu/stm/stm32l1xx/src/clock_stm32l1xx.c         | 253 +++++++++++++
 hw/mcu/stm/stm32l1xx/src/system_stm32l1xx.c        | 337 +++++++++++++++++
 hw/mcu/stm/stm32l1xx/syscfg.yml                    |  72 ++++
 7 files changed, 706 insertions(+), 481 deletions(-)

diff --git a/hw/bsp/stm32l152discovery/include/bsp/stm32l1xx_hal_conf.h b/hw/bsp/stm32l152discovery/include/bsp/stm32l1xx_hal_conf.h
index 098d4ac..b5ce2cb 100644
--- a/hw/bsp/stm32l152discovery/include/bsp/stm32l1xx_hal_conf.h
+++ b/hw/bsp/stm32l152discovery/include/bsp/stm32l1xx_hal_conf.h
@@ -2,7 +2,7 @@
   ******************************************************************************
   * @file    stm32l1xx_hal_conf.h
   * @author  MCD Application Team
-  * @brief   HAL configuration file. 
+  * @brief   HAL configuration file.
   ******************************************************************************
   * @attention
   *
@@ -31,12 +31,14 @@
   * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
   *
   ******************************************************************************
-  */ 
+  */
 
 /* Define to prevent recursive inclusion -------------------------------------*/
 #ifndef __STM32L1xx_HAL_CONF_H
 #define __STM32L1xx_HAL_CONF_H
 
+#include <syscfg/syscfg.h>
+
 #ifdef __cplusplus
  extern "C" {
 #endif
@@ -46,7 +48,7 @@
 
 /* ########################## Module Selection ############################## */
 /**
-  * @brief This is the list of modules to be used in the HAL driver 
+  * @brief This is the list of modules to be used in the HAL driver
   */
 #define HAL_MODULE_ENABLED
 /* #define HAL_ADC_MODULE_ENABLED */
@@ -82,9 +84,9 @@
 /**
   * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
   *        This value is used by the RCC HAL module to compute the system frequency
-  *        (when HSE is used as system clock source, directly or through the PLL).  
+  *        (when HSE is used as system clock source, directly or through the PLL).
   */
-#if !defined  (HSE_VALUE) 
+#if !defined  (HSE_VALUE)
   #define HSE_VALUE    (8000000U) /*!< Value of the External oscillator in Hz */
 #endif /* HSE_VALUE */
 
@@ -102,7 +104,7 @@
 /**
   * @brief Internal High Speed oscillator (HSI) value.
   *        This value is used by the RCC HAL module to compute the system frequency
-  *        (when HSI is used as system clock source, directly or through the PLL). 
+  *        (when HSI is used as system clock source, directly or through the PLL).
   */
 #if !defined  (HSI_VALUE)
   #define HSI_VALUE    (16000000U) /*!< Value of the Internal oscillator in Hz*/
@@ -122,37 +124,36 @@
   #define LSE_STARTUP_TIMEOUT    (5000U)   /*!< Time out for LSE start up, in ms */
 #endif /* LSE_STARTUP_TIMEOUT */
 
-   
 /* Tip: To avoid modifying this file each time you need to use different HSE,
    ===  you can define the HSE value in your toolchain compiler preprocessor. */
 
 /* ########################### System Configuration ######################### */
 /**
   * @brief This is the HAL system configuration section
-  */     
-#define  VDD_VALUE                    (3300U) /*!< Value of VDD in mv */          
-#define  TICK_INT_PRIORITY            (0x000FU)    /*!< tick interrupt priority */            
-#define  USE_RTOS                     0U     
-#define  PREFETCH_ENABLE              1U
-#define  INSTRUCTION_CACHE_ENABLE     0U
-#define  DATA_CACHE_ENABLE            0U
+  */
+#define  VDD_VALUE                    (3300U) /*!< Value of VDD in mv */
+#define  TICK_INT_PRIORITY            (0x000FU)    /*!< tick interrupt priority */
+#define  USE_RTOS                     0U
+#define  PREFETCH_ENABLE              MYNEWT_VAL(STM32_FLASH_PREFETCH_ENABLE)
+#define  INSTRUCTION_CACHE_ENABLE     MYNEWT_VAL(STM32_INSTRUCTION_CACHE_ENABLE)
+#define  DATA_CACHE_ENABLE            MYNEWT_VAL(STM32_DATA_CACHE_ENABLE)
 
 /* ########################## Assert Selection ############################## */
 /**
-  * @brief Uncomment the line below to expanse the "assert_param" macro in the 
+  * @brief Uncomment the line below to expanse the "assert_param" macro in the
   *        HAL drivers code
   */
-/*#define USE_FULL_ASSERT    1U*/ 
+/*#define USE_FULL_ASSERT    1U*/
 
 /* Includes ------------------------------------------------------------------*/
 /**
-  * @brief Include module's header file 
+  * @brief Include module's header file
   */
 
 #ifdef HAL_RCC_MODULE_ENABLED
  #include "stm32l1xx_hal_rcc.h"
 #endif /* HAL_RCC_MODULE_ENABLED */
-  
+
 #ifdef HAL_GPIO_MODULE_ENABLED
  #include "stm32l1xx_hal_gpio.h"
 #endif /* HAL_GPIO_MODULE_ENABLED */
@@ -195,7 +196,7 @@
 
 #ifdef HAL_NOR_MODULE_ENABLED
  #include "stm32l1xx_hal_nor.h"
-#endif /* HAL_NOR_MODULE_ENABLED */ 
+#endif /* HAL_NOR_MODULE_ENABLED */
 
 #ifdef HAL_I2C_MODULE_ENABLED
  #include "stm32l1xx_hal_i2c.h"
@@ -212,7 +213,7 @@
 #ifdef HAL_LCD_MODULE_ENABLED
  #include "stm32l1xx_hal_lcd.h"
 #endif /* HAL_LCD_MODULE_ENABLED */
-   
+
 #ifdef HAL_OPAMP_MODULE_ENABLED
  #include "stm32l1xx_hal_opamp.h"
 #endif /* HAL_OPAMP_MODULE_ENABLED */
@@ -227,7 +228,7 @@
 
 #ifdef HAL_SD_MODULE_ENABLED
  #include "stm32l1xx_hal_sd.h"
-#endif /* HAL_SD_MODULE_ENABLED */     
+#endif /* HAL_SD_MODULE_ENABLED */
 
 #ifdef HAL_SPI_MODULE_ENABLED
  #include "stm32l1xx_hal_spi.h"
@@ -260,14 +261,14 @@
 #ifdef HAL_PCD_MODULE_ENABLED
  #include "stm32l1xx_hal_pcd.h"
 #endif /* HAL_PCD_MODULE_ENABLED */
-   
+
 /* Exported macro ------------------------------------------------------------*/
 #ifdef  USE_FULL_ASSERT
 /**
   * @brief  The assert_param macro is used for function's parameters check.
   * @param  expr: If expr is false, it calls assert_failed function
   *         which reports the name of the source file and the source
-  *         line number of the call that failed. 
+  *         line number of the call that failed.
   *         If expr is true, it returns no value.
   * @retval None
   */
@@ -276,13 +277,12 @@
   void assert_failed(uint8_t* file, uint32_t line);
 #else
   #define assert_param(expr) ((void)0U)
-#endif /* USE_FULL_ASSERT */   
-   
+#endif /* USE_FULL_ASSERT */
+
 #ifdef __cplusplus
 }
 #endif
 
 #endif /* __STM32L1xx_HAL_CONF_H */
 
-
 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/hw/bsp/stm32l152discovery/src/hal_bsp.c b/hw/bsp/stm32l152discovery/src/hal_bsp.c
index 4f47958..dd8bfdc 100644
--- a/hw/bsp/stm32l152discovery/src/hal_bsp.c
+++ b/hw/bsp/stm32l152discovery/src/hal_bsp.c
@@ -118,46 +118,6 @@ hal_bsp_core_dump(int *area_cnt)
     return dump_cfg;
 }
 
-static void
-clock_config(void)
-{
-    RCC_ClkInitTypeDef RCC_ClkInitStruct = { 0 };
-    RCC_OscInitTypeDef RCC_OscInitStruct = { 0 };
-
-    /* Enable HSI Oscillator and Activate PLL with HSI as source */
-    RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
-    RCC_OscInitStruct.HSIState = RCC_HSI_ON;
-    RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
-    RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
-    RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
-    RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL6;
-    RCC_OscInitStruct.PLL.PLLDIV = RCC_PLL_DIV3;
-    if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) {
-        assert(0);
-    }
-
-    /* Set Voltage scale1 as MCU will run at 32MHz */
-    __HAL_RCC_PWR_CLK_ENABLE();
-    __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
-
-    /* Poll VOSF bit of in PWR_CSR. Wait until it is reset to 0 */
-    while (__HAL_PWR_GET_FLAG(PWR_FLAG_VOS) != RESET) ;
-
-    /*
-     * Select PLL as system clock source and configure the HCLK, PCLK1 and PCLK2
-     * clocks dividers
-     */
-    RCC_ClkInitStruct.ClockType = (RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK | \
-                                   RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2);
-    RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
-    RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
-    RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
-    RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
-    if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK) {
-        assert(0);
-    }
-}
-
 void
 hal_bsp_init(void)
 {
@@ -165,8 +125,6 @@ hal_bsp_init(void)
 
     (void)rc;
 
-    clock_config();
-
 #if MYNEWT_VAL(UART_0)
     rc = os_dev_create((struct os_dev *) &hal_uart0, "uart0",
       OS_DEV_INIT_PRIMARY, 0, uart_hal_init, (void *)&uart_cfg[0]);
diff --git a/hw/bsp/stm32l152discovery/src/system_stm32l1xx.c b/hw/bsp/stm32l152discovery/src/system_stm32l1xx.c
deleted file mode 100644
index a2e769a..0000000
--- a/hw/bsp/stm32l152discovery/src/system_stm32l1xx.c
+++ /dev/null
@@ -1,413 +0,0 @@
-/**
-  ******************************************************************************
-  * @file    system_stm32l1xx.c
-  * @author  MCD Application Team
-  * @brief   CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.
-  *             
-  *   This file provides two functions and one global variable to be called from 
-  *   user application:
-  *      - SystemInit(): This function is called at startup just after reset and 
-  *                      before branch to main program. This call is made inside
-  *                      the "startup_stm32l1xx.s" file.
-  *                        
-  *      - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
-  *                                  by the user application to setup the SysTick 
-  *                                  timer or configure other parameters.
-  *                                     
-  *      - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
-  *                                 be called whenever the core clock is changed
-  *                                 during program execution.   
-  *      
-  ******************************************************************************
-  * @attention
-  *
-  * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
-  *
-  * 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 of STMicroelectronics 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 HOLDER 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.
-  *
-  ******************************************************************************
-  */
-
-/** @addtogroup CMSIS
-  * @{
-  */
-
-/** @addtogroup stm32l1xx_system
-  * @{
-  */  
-  
-/** @addtogroup STM32L1xx_System_Private_Includes
-  * @{
-  */
-
-#include "stm32l1xx.h"
-#include "mcu/cmsis_nvic.h"
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L1xx_System_Private_TypesDefinitions
-  * @{
-  */
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L1xx_System_Private_Defines
-  * @{
-  */
-#if !defined  (HSE_VALUE) 
-  #define HSE_VALUE    ((uint32_t)8000000U) /*!< Default value of the External oscillator in Hz.
-                                                This value can be provided and adapted by the user application. */
-#endif /* HSE_VALUE */
-
-#if !defined  (HSI_VALUE)
-  #define HSI_VALUE    ((uint32_t)8000000U) /*!< Default value of the Internal oscillator in Hz.
-                                                This value can be provided and adapted by the user application. */
-#endif /* HSI_VALUE */
-
-/*!< Uncomment the following line if you need to use external SRAM mounted
-     on STM32L152D_EVAL board as data memory  */
-/* #define DATA_IN_ExtSRAM */
-  
-/*!< Uncomment the following line if you need to relocate your vector Table in
-     Internal SRAM. */ 
-/* #define VECT_TAB_SRAM */
-#define VECT_TAB_OFFSET  0x00U /*!< Vector Table base offset field. 
-                                  This value must be a multiple of 0x200. */
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L1xx_System_Private_Macros
-  * @{
-  */
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L1xx_System_Private_Variables
-  * @{
-  */
-  /* This variable is updated in three ways:
-      1) by calling CMSIS function SystemCoreClockUpdate()
-      2) by calling HAL API function HAL_RCC_GetHCLKFreq()
-      3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
-         Note: If you use this function to configure the system clock; then there
-               is no need to call the 2 first functions listed above, since SystemCoreClock
-               variable is updated automatically.
-  */
-uint32_t SystemCoreClock    = 32000000;
-const uint8_t PLLMulTable[9]    = {3U, 4U, 6U, 8U, 12U, 16U, 24U, 32U, 48U};
-const uint8_t AHBPrescTable[16] = {0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U};
-const uint8_t APBPrescTable[8]  = {0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U};
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L1xx_System_Private_FunctionPrototypes
-  * @{
-  */
-
-#if defined (STM32L151xD) || defined (STM32L152xD) || defined (STM32L162xD)
-#ifdef DATA_IN_ExtSRAM
-  static void SystemInit_ExtMemCtl(void); 
-#endif /* DATA_IN_ExtSRAM */
-#endif /* STM32L151xD || STM32L152xD || STM32L162xD */
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L1xx_System_Private_Functions
-  * @{
-  */
-
-/**
-  * @brief  Setup the microcontroller system.
-  *         Initialize the Embedded Flash Interface, the PLL and update the 
-  *         SystemCoreClock variable.
-  * @param  None
-  * @retval None
-  */
-void SystemInit (void)
-{
-  /*!< Set MSION bit */
-  RCC->CR |= (uint32_t)0x00000100;
-
-  /*!< Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], MCOSEL[2:0] and MCOPRE[2:0] bits */
-  RCC->CFGR &= (uint32_t)0x88FFC00C;
-
-  /*!< Reset HSION, HSEON, CSSON and PLLON bits */
-  RCC->CR &= (uint32_t)0xEEFEFFFE;
-
-  /*!< Reset HSEBYP bit */
-  RCC->CR &= (uint32_t)0xFFFBFFFF;
-
-  /*!< Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */
-  RCC->CFGR &= (uint32_t)0xFF02FFFF;
-
-  /*!< Disable all interrupts */
-  RCC->CIR = 0x00000000;
-
-#ifdef DATA_IN_ExtSRAM
-  SystemInit_ExtMemCtl();
-#endif /* DATA_IN_ExtSRAM */
-
-  /* Relocate the vector table */
-  NVIC_Relocate();
-}
-
-/**
-  * @brief  Update SystemCoreClock according to Clock Register Values
-  *         The SystemCoreClock variable contains the core clock (HCLK), it can
-  *         be used by the user application to setup the SysTick timer or configure
-  *         other parameters.
-  *           
-  * @note   Each time the core clock (HCLK) changes, this function must be called
-  *         to update SystemCoreClock variable value. Otherwise, any configuration
-  *         based on this variable will be incorrect.         
-  *     
-  * @note   - The system frequency computed by this function is not the real 
-  *           frequency in the chip. It is calculated based on the predefined 
-  *           constant and the selected clock source:
-  *             
-  *           - If SYSCLK source is MSI, SystemCoreClock will contain the MSI 
-  *             value as defined by the MSI range.
-  *                                   
-  *           - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
-  *                                              
-  *           - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
-  *                          
-  *           - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
-  *             or HSI_VALUE(*) multiplied/divided by the PLL factors.
-  *         
-  *         (*) HSI_VALUE is a constant defined in stm32l1xx.h file (default value
-  *             16 MHz) but the real value may vary depending on the variations
-  *             in voltage and temperature.   
-  *    
-  *         (**) HSE_VALUE is a constant defined in stm32l1xx.h file (default value
-  *              8 MHz), user has to ensure that HSE_VALUE is same as the real
-  *              frequency of the crystal used. Otherwise, this function may
-  *              have wrong result.
-  *                
-  *         - The result of this function could be not correct when using fractional
-  *           value for HSE crystal.
-  * @param  None
-  * @retval None
-  */
-void SystemCoreClockUpdate (void)
-{
-  uint32_t tmp = 0, pllmul = 0, plldiv = 0, pllsource = 0, msirange = 0;
-
-  /* Get SYSCLK source -------------------------------------------------------*/
-  tmp = RCC->CFGR & RCC_CFGR_SWS;
-
-  switch (tmp)
-  {
-    case 0x00:  /* MSI used as system clock */
-      msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;
-      SystemCoreClock = (32768 * (1 << (msirange + 1)));
-      break;
-    case 0x04:  /* HSI used as system clock */
-      SystemCoreClock = HSI_VALUE;
-      break;
-    case 0x08:  /* HSE used as system clock */
-      SystemCoreClock = HSE_VALUE;
-      break;
-    case 0x0C:  /* PLL used as system clock */
-      /* Get PLL clock source and multiplication factor ----------------------*/
-      pllmul = RCC->CFGR & RCC_CFGR_PLLMUL;
-      plldiv = RCC->CFGR & RCC_CFGR_PLLDIV;
-      pllmul = PLLMulTable[(pllmul >> 18)];
-      plldiv = (plldiv >> 22) + 1;
-
-      pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
-
-      if (pllsource == 0x00)
-      {
-        /* HSI oscillator clock selected as PLL clock entry */
-        SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv);
-      }
-      else
-      {
-        /* HSE selected as PLL clock entry */
-        SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv);
-      }
-      break;
-    default: /* MSI used as system clock */
-      msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;
-      SystemCoreClock = (32768 * (1 << (msirange + 1)));
-      break;
-  }
-  /* Compute HCLK clock frequency --------------------------------------------*/
-  /* Get HCLK prescaler */
-  tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
-  /* HCLK clock frequency */
-  SystemCoreClock >>= tmp;
-}
-
-#if defined (STM32L151xD) || defined (STM32L152xD) || defined (STM32L162xD)
-#ifdef DATA_IN_ExtSRAM
-/**
-  * @brief  Setup the external memory controller.
-  *         Called in SystemInit() function before jump to main.
-  *         This function configures the external SRAM mounted on STM32L152D_EVAL board
-  *         This SRAM will be used as program data memory (including heap and stack).
-  * @param  None
-  * @retval None
-  */
-void SystemInit_ExtMemCtl(void)
-{
-/*-- GPIOs Configuration -----------------------------------------------------*/
-/*
- +-------------------+--------------------+------------------+------------------+
- +                       SRAM pins assignment                                   +
- +-------------------+--------------------+------------------+------------------+
- | PD0  <-> FSMC_D2  | PE0  <-> FSMC_NBL0 | PF0  <-> FSMC_A0 | PG0 <-> FSMC_A10 |
- | PD1  <-> FSMC_D3  | PE1  <-> FSMC_NBL1 | PF1  <-> FSMC_A1 | PG1 <-> FSMC_A11 |
- | PD4  <-> FSMC_NOE | PE7  <-> FSMC_D4   | PF2  <-> FSMC_A2 | PG2 <-> FSMC_A12 |
- | PD5  <-> FSMC_NWE | PE8  <-> FSMC_D5   | PF3  <-> FSMC_A3 | PG3 <-> FSMC_A13 |
- | PD8  <-> FSMC_D13 | PE9  <-> FSMC_D6   | PF4  <-> FSMC_A4 | PG4 <-> FSMC_A14 |
- | PD9  <-> FSMC_D14 | PE10 <-> FSMC_D7   | PF5  <-> FSMC_A5 | PG5 <-> FSMC_A15 |
- | PD10 <-> FSMC_D15 | PE11 <-> FSMC_D8   | PF12 <-> FSMC_A6 | PG10<-> FSMC_NE2 |
- | PD11 <-> FSMC_A16 | PE12 <-> FSMC_D9   | PF13 <-> FSMC_A7 |------------------+
- | PD12 <-> FSMC_A17 | PE13 <-> FSMC_D10  | PF14 <-> FSMC_A8 | 
- | PD13 <-> FSMC_A18 | PE14 <-> FSMC_D11  | PF15 <-> FSMC_A9 | 
- | PD14 <-> FSMC_D0  | PE15 <-> FSMC_D12  |------------------+
- | PD15 <-> FSMC_D1  |--------------------+ 
- +-------------------+
-*/
-
-  /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
-  RCC->AHBENR   = 0x000080D8;
-  
-  /* Connect PDx pins to FSMC Alternate function */
-  GPIOD->AFR[0]  = 0x00CC00CC;
-  GPIOD->AFR[1]  = 0xCCCCCCCC;
-  /* Configure PDx pins in Alternate function mode */  
-  GPIOD->MODER   = 0xAAAA0A0A;
-  /* Configure PDx pins speed to 40 MHz */  
-  GPIOD->OSPEEDR = 0xFFFF0F0F;
-  /* Configure PDx pins Output type to push-pull */  
-  GPIOD->OTYPER  = 0x00000000;
-  /* No pull-up, pull-down for PDx pins */ 
-  GPIOD->PUPDR   = 0x00000000;
-
-  /* Connect PEx pins to FSMC Alternate function */
-  GPIOE->AFR[0]  = 0xC00000CC;
-  GPIOE->AFR[1]  = 0xCCCCCCCC;
-  /* Configure PEx pins in Alternate function mode */ 
-  GPIOE->MODER   = 0xAAAA800A;
-  /* Configure PEx pins speed to 40 MHz */ 
-  GPIOE->OSPEEDR = 0xFFFFC00F;
-  /* Configure PEx pins Output type to push-pull */  
-  GPIOE->OTYPER  = 0x00000000;
-  /* No pull-up, pull-down for PEx pins */ 
-  GPIOE->PUPDR   = 0x00000000;
-
-  /* Connect PFx pins to FSMC Alternate function */
-  GPIOF->AFR[0]  = 0x00CCCCCC;
-  GPIOF->AFR[1]  = 0xCCCC0000;
-  /* Configure PFx pins in Alternate function mode */   
-  GPIOF->MODER   = 0xAA000AAA;
-  /* Configure PFx pins speed to 40 MHz */ 
-  GPIOF->OSPEEDR = 0xFF000FFF;
-  /* Configure PFx pins Output type to push-pull */  
-  GPIOF->OTYPER  = 0x00000000;
-  /* No pull-up, pull-down for PFx pins */ 
-  GPIOF->PUPDR   = 0x00000000;
-
-  /* Connect PGx pins to FSMC Alternate function */
-  GPIOG->AFR[0]  = 0x00CCCCCC;
-  GPIOG->AFR[1]  = 0x00000C00;
-  /* Configure PGx pins in Alternate function mode */ 
-  GPIOG->MODER   = 0x00200AAA;
-  /* Configure PGx pins speed to 40 MHz */ 
-  GPIOG->OSPEEDR = 0x00300FFF;
-  /* Configure PGx pins Output type to push-pull */  
-  GPIOG->OTYPER  = 0x00000000;
-  /* No pull-up, pull-down for PGx pins */ 
-  GPIOG->PUPDR   = 0x00000000;
-  
-/*-- FSMC Configuration ------------------------------------------------------*/
-  /* Enable the FSMC interface clock */
-  RCC->AHBENR    = 0x400080D8;
-
-  /* Configure and enable Bank1_SRAM3 */
-  FSMC_Bank1->BTCR[4]  = 0x00001011;
-  FSMC_Bank1->BTCR[5]  = 0x00000300;
-  FSMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
-/*
-  Bank1_SRAM3 is configured as follow:
-
-  p.FSMC_AddressSetupTime = 0;
-  p.FSMC_AddressHoldTime = 0;
-  p.FSMC_DataSetupTime = 3;
-  p.FSMC_BusTurnAroundDuration = 0;
-  p.FSMC_CLKDivision = 0;
-  p.FSMC_DataLatency = 0;
-  p.FSMC_AccessMode = FSMC_AccessMode_A;
-
-  FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM3;
-  FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
-  FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
-  FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
-  FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
-  FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
-  FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
-  FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
-  FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
-  FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
-  FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
-  FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
-  FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
-  FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
-  FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
-
-  FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure); 
-
-  FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM3, ENABLE);
-*/
-  
-}
-#endif /* DATA_IN_ExtSRAM */
-#endif /* STM32L151xD || STM32L152xD || STM32L162xD */
-
-/**
-  * @}
-  */
-
-/**
-  * @}
-  */
-
-/**
-  * @}
-  */
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/hw/bsp/stm32l152discovery/syscfg.yml b/hw/bsp/stm32l152discovery/syscfg.yml
index 8ec97cd..ee7cbb0 100644
--- a/hw/bsp/stm32l152discovery/syscfg.yml
+++ b/hw/bsp/stm32l152discovery/syscfg.yml
@@ -43,3 +43,21 @@ syscfg.vals:
     CONFIG_FCB_FLASH_AREA: FLASH_AREA_NFFS
     NFFS_FLASH_AREA: FLASH_AREA_NFFS
     COREDUMP_FLASH_AREA: FLASH_AREA_IMAGE_1
+    STM32_CLOCK_VOLTAGESCALING_CONFIG: 'PWR_REGULATOR_VOLTAGE_SCALE1'
+    STM32_CLOCK_LSI: 1
+    STM32_CLOCK_LSE: 0
+    STM32_CLOCK_LSE_BYPASS: 0
+    STM32_CLOCK_MSI: 0
+    STM32_CLOCK_MSI_CALIBRATION: 0
+    STM32_CLOCK_MSI_CLOCK_RANGE: 'RCC_MSIRANGE_5'  # 2.097MHz
+    STM32_CLOCK_HSI: 1
+    STM32_CLOCK_HSI_CALIBRATION: 16
+    STM32_CLOCK_HSE: 0
+    STM32_CLOCK_HSE_BYPASS: 0
+    STM32_CLOCK_PLL_MUL: 'RCC_PLL_MUL4'  # 16 * 4 = 64MHz
+    STM32_CLOCK_PLL_DIV: 'RCC_PLL_DIV2'  # 64 / 2 = 32MHz
+    STM32_CLOCK_AHB_DIVIDER: 'RCC_SYSCLK_DIV1'
+    STM32_CLOCK_APB1_DIVIDER: 'RCC_HCLK_DIV1'
+    STM32_CLOCK_APB2_DIVIDER: 'RCC_HCLK_DIV1'
+    STM32_FLASH_LATENCY: 1  # max 32MHz
+    STM32_FLASH_PREFETCH_ENABLE: 0
diff --git a/hw/mcu/stm/stm32l1xx/src/clock_stm32l1xx.c b/hw/mcu/stm/stm32l1xx/src/clock_stm32l1xx.c
new file mode 100644
index 0000000..ff20d3a
--- /dev/null
+++ b/hw/mcu/stm/stm32l1xx/src/clock_stm32l1xx.c
@@ -0,0 +1,253 @@
+/*
+ * <h2><center>&copy; COPYRIGHT 2016 STMicroelectronics</center></h2>
+ *
+ * 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 of STMicroelectronics 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 HOLDER 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.
+ */
+
+#include "stm32l1xx_hal_pwr_ex.h"
+#include "stm32l1xx_hal_rcc.h"
+#include "stm32l1xx_hal.h"
+#include <assert.h>
+
+/*
+ * This allows an user to have a custom clock configuration by zeroing
+ * every possible clock source in the syscfg.
+ */
+#if MYNEWT_VAL(STM32_CLOCK_MSI) || MYNEWT_VAL(STM32_CLOCK_HSE) || \
+    MYNEWT_VAL(STM32_CLOCK_LSE) || MYNEWT_VAL(STM32_CLOCK_HSI) || \
+    MYNEWT_VAL(STM32_CLOCK_LSI)
+
+/*
+ * MSI is turned on by default, but can be turned off and use HSE/HSI instead.
+ */
+#if (((MYNEWT_VAL(STM32_CLOCK_MSI) != 0) + \
+      (MYNEWT_VAL(STM32_CLOCK_HSE) != 0) + \
+      (MYNEWT_VAL(STM32_CLOCK_HSI) != 0)) < 1)
+#error "At least one of MSI, HSE or HSI clock sources must be enabled"
+#endif
+
+void
+SystemClock_Config(void)
+{
+    RCC_OscInitTypeDef osc_init;
+    RCC_ClkInitTypeDef clk_init;
+    HAL_StatusTypeDef status;
+
+    /*
+     * The voltage scaling allows optimizing the power consumption when the
+     * device is clocked below the maximum system frequency, to update the
+     * voltage scaling value regarding system frequency refer to product
+     * datasheet.
+     */
+    __HAL_PWR_VOLTAGESCALING_CONFIG(MYNEWT_VAL(STM32_CLOCK_VOLTAGESCALING_CONFIG));
+
+    osc_init.OscillatorType = RCC_OSCILLATORTYPE_NONE;
+
+    /*
+     * LSI is used to clock the independent watchdog and optionally the RTC.
+     * It can be disabled per user request, but will be automatically enabled
+     * again when the IWDG is started.
+     *
+     * XXX currently the watchdog is not optional, so there's no point in
+     * disabling LSI through syscfg.
+     */
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_LSI;
+#if (MYNEWT_VAL(STM32_CLOCK_LSI) == 0)
+    osc_init.LSIState = RCC_LSI_OFF;
+#else
+    osc_init.LSIState = RCC_LSI_ON;
+#endif
+
+    /*
+     * LSE is only used to clock the RTC.
+     */
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_LSE;
+#if (MYNEWT_VAL(STM32_CLOCK_LSE) == 0)
+    osc_init.LSEState = RCC_LSE_OFF;
+#elif MYNEWT_VAL(STM32_CLOCK_LSE_BYPASS)
+    osc_init.LSEState = RCC_LSE_BYPASS;
+#else
+    osc_init.LSEState = RCC_LSE_ON;
+#endif
+
+    /*
+     * MSI Oscillator
+     */
+#if MYNEWT_VAL(STM32_CLOCK_MSI)
+
+#if (MYNEWT_VAL(STM32_CLOCK_MSI_CALIBRATION) > 255)
+#error "Invalid MSI calibration value"
+#endif
+#if !IS_RCC_MSI_CLOCK_RANGE(MYNEWT_VAL(STM32_CLOCK_MSI_CLOCK_RANGE))
+#error "Invalid MSI clock range"
+#endif
+
+    /* NOTE: MSI can't be disabled if it's the current PLL or SYSCLK source;
+     * leave it untouched in those cases, and disable later after a new source
+     * has been configured.
+     */
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_MSI;
+    osc_init.MSIState = RCC_MSI_ON;
+    osc_init.MSICalibrationValue = MYNEWT_VAL(STM32_CLOCK_MSI_CALIBRATION);
+    osc_init.MSIClockRange = MYNEWT_VAL(STM32_CLOCK_MSI_CLOCK_RANGE);
+#endif
+
+    /*
+     * HSE Oscillator (can be used as PLL, SYSCLK and RTC clock source)
+     */
+#if MYNEWT_VAL(STM32_CLOCK_HSE)
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_HSE;
+
+#if MYNEWT_VAL(STM32_CLOCK_HSE_BYPASS)
+    osc_init.HSEState = RCC_HSE_BYPASS;
+#else
+    osc_init.HSEState = RCC_HSE_ON;
+#endif
+
+#endif
+
+    /*
+     * HSI Oscillator (can be used as PLL and SYSCLK clock source). It is
+     * already turned on by default but a new calibration setting might be
+     * used. If the user chooses to turn it off, it must be turned off after
+     * SYSCLK was updated to use HSE/PLL.
+     */
+#if MYNEWT_VAL(STM32_CLOCK_HSI)
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_HSI;
+    osc_init.HSIState = RCC_HSI_ON;
+    /* HSI calibration is not optional when HSI is enabled */
+    osc_init.HSICalibrationValue = MYNEWT_VAL(STM32_CLOCK_HSI_CALIBRATION);
+
+#if (MYNEWT_VAL(STM32_CLOCK_HSI_CALIBRATION) > 31)
+#error "Invalid HSI calibration value"
+#endif
+#endif
+
+#if MYNEWT_VAL(STM32_CLOCK_MSI)
+
+    osc_init.PLL.PLLState = RCC_PLL_OFF;
+
+#else
+
+    /*
+     * Default to HSE or HSI as PLL source when multiple high-speed
+     * sources are enabled.
+     */
+    osc_init.PLL.PLLState = RCC_PLL_ON;
+#if MYNEWT_VAL(STM32_CLOCK_HSE)
+    osc_init.PLL.PLLSource = RCC_PLLSOURCE_HSE;
+#else
+    osc_init.PLL.PLLSource = RCC_PLLSOURCE_HSI;
+#endif
+
+#if !IS_RCC_PLL_MUL(MYNEWT_VAL(STM32_CLOCK_PLL_MUL))
+#error "PLL_MUL value is invalid"
+#endif
+
+#if !IS_RCC_PLL_DIV(MYNEWT_VAL(STM32_CLOCK_PLL_DIV))
+#error "PLL_DIV value is invalid"
+#endif
+
+    osc_init.PLL.PLLMUL = MYNEWT_VAL(STM32_CLOCK_PLL_MUL);
+    osc_init.PLL.PLLDIV = MYNEWT_VAL(STM32_CLOCK_PLL_DIV);
+
+    status = HAL_RCC_OscConfig(&osc_init);
+    if (status != HAL_OK) {
+        assert(0);
+    }
+
+#endif
+
+    /*
+     * Select PLL as system clock source and configure the HCLK*, PCLK* and
+     * SYSCLK clocks dividers. HSI, HSE and MSI are also valid system clock
+     * sources, although there is no much point in supporting them now.
+     */
+    clk_init.ClockType =  RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_HCLK |
+        RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
+#if MYNEWT_VAL(STM32_CLOCK_MSI)
+    clk_init.SYSCLKSource = RCC_SYSCLKSOURCE_MSI;
+#else
+    clk_init.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
+#endif
+
+#if !IS_RCC_HCLK(MYNEWT_VAL(STM32_CLOCK_AHB_DIVIDER))
+#error "AHB clock divider is invalid"
+#endif
+
+#if !IS_RCC_PCLK(MYNEWT_VAL(STM32_CLOCK_APB1_DIVIDER))
+#error "APB1 clock divider is invalid"
+#endif
+
+#if !IS_RCC_PCLK(MYNEWT_VAL(STM32_CLOCK_APB2_DIVIDER))
+#error "APB2 clock divider is invalid"
+#endif
+
+    clk_init.AHBCLKDivider = MYNEWT_VAL(STM32_CLOCK_AHB_DIVIDER);
+    clk_init.APB1CLKDivider = MYNEWT_VAL(STM32_CLOCK_APB1_DIVIDER);
+    clk_init.APB2CLKDivider = MYNEWT_VAL(STM32_CLOCK_APB2_DIVIDER);
+
+#if (MYNEWT_VAL(STM32_FLASH_LATENCY) != 0) && (MYNEWT_VAL(STM32_FLASH_LATENCY) != 1)
+#error "Flash latency value is invalid"
+#endif
+
+    status = HAL_RCC_ClockConfig(&clk_init, MYNEWT_VAL(STM32_FLASH_LATENCY));
+    if (status != HAL_OK) {
+        assert(0);
+    }
+
+#if ((MYNEWT_VAL(STM32_CLOCK_HSI) == 0) || (MYNEWT_VAL(STM32_CLOCK_HSE) == 0) || \
+     (MYNEWT_VAL(STM32_CLOCK_MSI) == 0))
+    /*
+     * Turn off HSE/HSI oscillator; this must be done at the end because
+     * SYSCLK source has to be updated first.
+     */
+    osc_init.OscillatorType = RCC_OSCILLATORTYPE_NONE;
+#if (MYNEWT_VAL(STM32_CLOCK_HSE) == 0)
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_HSE;
+    osc_init.HSEState = RCC_HSE_OFF;
+#endif
+#if (MYNEWT_VAL(STM32_CLOCK_HSI) == 0)
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_HSI;
+    osc_init.HSIState = RCC_HSI_OFF;
+#endif
+#if (MYNEWT_VAL(STM32_CLOCK_MSI) == 0)
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_MSI;
+    osc_init.MSIState = RCC_MSI_OFF;
+#endif
+
+#endif
+
+    osc_init.PLL.PLLState = RCC_PLL_NONE;
+
+    status = HAL_RCC_OscConfig(&osc_init);
+    if (status != HAL_OK) {
+        assert(0);
+    }
+
+#if PREFETCH_ENABLE
+    __HAL_FLASH_PREFETCH_BUFFER_ENABLE();
+#endif
+}
+
+#endif
diff --git a/hw/mcu/stm/stm32l1xx/src/system_stm32l1xx.c b/hw/mcu/stm/stm32l1xx/src/system_stm32l1xx.c
new file mode 100644
index 0000000..0d24392
--- /dev/null
+++ b/hw/mcu/stm/stm32l1xx/src/system_stm32l1xx.c
@@ -0,0 +1,337 @@
+/**
+  * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
+  *
+  * 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 of STMicroelectronics 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 HOLDER 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.
+  */
+
+#include <stdint.h>
+#include "bsp/stm32l1xx_hal_conf.h"
+#include "stm32l1xx.h"
+#include "mcu/cmsis_nvic.h"
+#include "mcu/stm32_hal.h"
+
+/* This variable is updated in three ways:
+  1) by calling CMSIS function SystemCoreClockUpdate()
+  2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+  3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+     Note: If you use this function to configure the system clock; then there
+           is no need to call the 2 first functions listed above, since SystemCoreClock
+           variable is updated automatically.
+*/
+
+uint32_t SystemCoreClock;
+const uint8_t PLLMulTable[9] = {
+    3U, 4U, 6U, 8U, 12U, 16U, 24U, 32U, 48U
+};
+const uint8_t AHBPrescTable[16] = {
+    0U, 0U, 0U, 0U, 0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U, 6U, 7U, 8U, 9U
+};
+const uint8_t APBPrescTable[8] = {
+    0U, 0U, 0U, 0U, 1U, 2U, 3U, 4U
+};
+
+#if defined(STM32L151xD) || defined(STM32L152xD) || defined(STM32L162xD)
+#ifdef DATA_IN_ExtSRAM
+  static void SystemInit_ExtMemCtl(void);
+#endif
+#endif
+
+/*
+ * XXX BSP specific
+ */
+void SystemClock_Config(void);
+
+/**
+  * @brief  Setup the microcontroller system.
+  *         Initialize the Embedded Flash Interface, the PLL and update the 
+  *         SystemCoreClock variable.
+  * @param  None
+  * @retval None
+  */
+void
+SystemInit(void)
+{
+    /* Set MSION bit */
+    RCC->CR |= (uint32_t)0x00000100;
+
+    /* Reset SW[1:0], HPRE[3:0], PPRE1[2:0], PPRE2[2:0], MCOSEL[2:0] and MCOPRE[2:0] bits */
+    RCC->CFGR &= (uint32_t)0x88FFC00C;
+
+    /* Reset HSION, HSEON, CSSON and PLLON bits */
+    RCC->CR &= (uint32_t)0xEEFEFFFE;
+
+    /* Reset HSEBYP bit */
+    RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+    /* Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */
+    RCC->CFGR &= (uint32_t)0xFF02FFFF;
+
+    /* Disable all interrupts */
+    RCC->CIR = 0x00000000;
+
+#ifdef DATA_IN_ExtSRAM
+    SystemInit_ExtMemCtl();
+#endif
+
+    /* Configure System Clock */
+    SystemClock_Config();
+
+    /* Update SystemCoreClock global variable */
+    SystemCoreClockUpdate();
+
+    /* Relocate the vector table */
+    NVIC_Relocate();
+}
+
+/**
+  * @brief  Update SystemCoreClock according to Clock Register Values
+  *         The SystemCoreClock variable contains the core clock (HCLK), it can
+  *         be used by the user application to setup the SysTick timer or configure
+  *         other parameters.
+  *
+  * @note   Each time the core clock (HCLK) changes, this function must be called
+  *         to update SystemCoreClock variable value. Otherwise, any configuration
+  *         based on this variable will be incorrect.
+  *
+  * @note   - The system frequency computed by this function is not the real
+  *           frequency in the chip. It is calculated based on the predefined
+  *           constant and the selected clock source:
+  *
+  *           - If SYSCLK source is MSI, SystemCoreClock will contain the MSI
+  *             value as defined by the MSI range.
+  *
+  *           - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+  *
+  *           - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+  *
+  *           - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+  *             or HSI_VALUE(*) multiplied/divided by the PLL factors.
+  *
+  *         (*) HSI_VALUE is a constant defined in stm32l1xx.h file (default value
+  *             16 MHz) but the real value may vary depending on the variations
+  *             in voltage and temperature.
+  *
+  *         (**) HSE_VALUE is a constant defined in stm32l1xx.h file (default value
+  *              8 MHz), user has to ensure that HSE_VALUE is same as the real
+  *              frequency of the crystal used. Otherwise, this function may
+  *              have wrong result.
+  *
+  *         - The result of this function could be not correct when using fractional
+  *           value for HSE crystal.
+  * @param  None
+  * @retval None
+  */
+void
+SystemCoreClockUpdate(void)
+{
+    uint32_t tmp;
+    uint32_t pllmul;
+    uint32_t plldiv;
+    uint32_t pllsource;
+    uint32_t msirange;
+
+    /*
+     * Get SYSCLK source
+     */
+    tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+    switch (tmp) {
+    /* HSI used as system clock */
+    case 0x04:
+        SystemCoreClock = HSI_VALUE;
+        break;
+
+    /* HSE used as system clock */
+    case 0x08:
+        SystemCoreClock = HSE_VALUE;
+        break;
+
+    /* PLL used as system clock */
+    case 0x0C:
+        /*
+         * Get PLL clock source and multiplication factor
+         */
+        pllmul = RCC->CFGR & RCC_CFGR_PLLMUL;
+        plldiv = RCC->CFGR & RCC_CFGR_PLLDIV;
+        pllmul = PLLMulTable[(pllmul >> 18)];
+        plldiv = (plldiv >> 22) + 1;
+
+        pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+
+        if (pllsource == 0x00) {
+            /* HSI oscillator clock selected as PLL clock entry */
+            SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv);
+        } else {
+            /* HSE selected as PLL clock entry */
+            SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv);
+        }
+        break;
+
+    /* MSI used as system clock */
+    default:
+        msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> 13;
+        SystemCoreClock = (32768 * (1 << (msirange + 1)));
+        break;
+    }
+
+    /*
+     * Compute HCLK clock frequency
+     */
+
+    /* Get HCLK prescaler */
+    tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+
+    /* HCLK clock frequency */
+    SystemCoreClock >>= tmp;
+}
+
+#if defined (STM32L151xD) || defined (STM32L152xD) || defined (STM32L162xD)
+#ifdef DATA_IN_ExtSRAM
+/**
+  * FIXME: all DATA_IN_ExtSRAM implementations should be moved to BSP.
+  *
+  * @brief  Setup the external memory controller.
+  *         Called in SystemInit() function before jump to main.
+  *         This function configures the external SRAM mounted on STM32L152D_EVAL board
+  *         This SRAM will be used as program data memory (including heap and stack).
+  * @param  None
+  * @retval None
+  */
+void
+SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+------------------+
+ +                       SRAM pins assignment                                   +
+ +-------------------+--------------------+------------------+------------------+
+ | PD0  <-> FSMC_D2  | PE0  <-> FSMC_NBL0 | PF0  <-> FSMC_A0 | PG0 <-> FSMC_A10 |
+ | PD1  <-> FSMC_D3  | PE1  <-> FSMC_NBL1 | PF1  <-> FSMC_A1 | PG1 <-> FSMC_A11 |
+ | PD4  <-> FSMC_NOE | PE7  <-> FSMC_D4   | PF2  <-> FSMC_A2 | PG2 <-> FSMC_A12 |
+ | PD5  <-> FSMC_NWE | PE8  <-> FSMC_D5   | PF3  <-> FSMC_A3 | PG3 <-> FSMC_A13 |
+ | PD8  <-> FSMC_D13 | PE9  <-> FSMC_D6   | PF4  <-> FSMC_A4 | PG4 <-> FSMC_A14 |
+ | PD9  <-> FSMC_D14 | PE10 <-> FSMC_D7   | PF5  <-> FSMC_A5 | PG5 <-> FSMC_A15 |
+ | PD10 <-> FSMC_D15 | PE11 <-> FSMC_D8   | PF12 <-> FSMC_A6 | PG10<-> FSMC_NE2 |
+ | PD11 <-> FSMC_A16 | PE12 <-> FSMC_D9   | PF13 <-> FSMC_A7 |------------------+
+ | PD12 <-> FSMC_A17 | PE13 <-> FSMC_D10  | PF14 <-> FSMC_A8 |
+ | PD13 <-> FSMC_A18 | PE14 <-> FSMC_D11  | PF15 <-> FSMC_A9 |
+ | PD14 <-> FSMC_D0  | PE15 <-> FSMC_D12  |------------------+
+ | PD15 <-> FSMC_D1  |--------------------+
+ +-------------------+
+*/
+
+    /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+    RCC->AHBENR   = 0x000080D8;
+
+    /* Connect PDx pins to FSMC Alternate function */
+    GPIOD->AFR[0]  = 0x00CC00CC;
+    GPIOD->AFR[1]  = 0xCCCCCCCC;
+    /* Configure PDx pins in Alternate function mode */
+    GPIOD->MODER   = 0xAAAA0A0A;
+    /* Configure PDx pins speed to 40 MHz */
+    GPIOD->OSPEEDR = 0xFFFF0F0F;
+    /* Configure PDx pins Output type to push-pull */
+    GPIOD->OTYPER  = 0x00000000;
+    /* No pull-up, pull-down for PDx pins */
+    GPIOD->PUPDR   = 0x00000000;
+
+    /* Connect PEx pins to FSMC Alternate function */
+    GPIOE->AFR[0]  = 0xC00000CC;
+    GPIOE->AFR[1]  = 0xCCCCCCCC;
+    /* Configure PEx pins in Alternate function mode */
+    GPIOE->MODER   = 0xAAAA800A;
+    /* Configure PEx pins speed to 40 MHz */
+    GPIOE->OSPEEDR = 0xFFFFC00F;
+    /* Configure PEx pins Output type to push-pull */
+    GPIOE->OTYPER  = 0x00000000;
+    /* No pull-up, pull-down for PEx pins */
+    GPIOE->PUPDR   = 0x00000000;
+
+    /* Connect PFx pins to FSMC Alternate function */
+    GPIOF->AFR[0]  = 0x00CCCCCC;
+    GPIOF->AFR[1]  = 0xCCCC0000;
+    /* Configure PFx pins in Alternate function mode */
+    GPIOF->MODER   = 0xAA000AAA;
+    /* Configure PFx pins speed to 40 MHz */
+    GPIOF->OSPEEDR = 0xFF000FFF;
+    /* Configure PFx pins Output type to push-pull */
+    GPIOF->OTYPER  = 0x00000000;
+    /* No pull-up, pull-down for PFx pins */
+    GPIOF->PUPDR   = 0x00000000;
+
+    /* Connect PGx pins to FSMC Alternate function */
+    GPIOG->AFR[0]  = 0x00CCCCCC;
+    GPIOG->AFR[1]  = 0x00000C00;
+    /* Configure PGx pins in Alternate function mode */
+    GPIOG->MODER   = 0x00200AAA;
+    /* Configure PGx pins speed to 40 MHz */
+    GPIOG->OSPEEDR = 0x00300FFF;
+    /* Configure PGx pins Output type to push-pull */
+    GPIOG->OTYPER  = 0x00000000;
+    /* No pull-up, pull-down for PGx pins */
+    GPIOG->PUPDR   = 0x00000000;
+
+/*-- FSMC Configuration ------------------------------------------------------*/
+    /* Enable the FSMC interface clock */
+    RCC->AHBENR    = 0x400080D8;
+
+    /* Configure and enable Bank1_SRAM3 */
+    FSMC_Bank1->BTCR[4]  = 0x00001011;
+    FSMC_Bank1->BTCR[5]  = 0x00000300;
+    FSMC_Bank1E->BWTR[4] = 0x0FFFFFFF;
+/*
+    Bank1_SRAM3 is configured as follow:
+
+    p.FSMC_AddressSetupTime = 0;
+    p.FSMC_AddressHoldTime = 0;
+    p.FSMC_DataSetupTime = 3;
+    p.FSMC_BusTurnAroundDuration = 0;
+    p.FSMC_CLKDivision = 0;
+    p.FSMC_DataLatency = 0;
+    p.FSMC_AccessMode = FSMC_AccessMode_A;
+
+    FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM3;
+    FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+    FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+    FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+    FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+    FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+    FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+    FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+    FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+    FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+    FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+    FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+    FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+    FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
+    FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
+
+    FSMC_NORSRAMInit(&FSMC_NORSRAMInitStructure); 
+
+    FSMC_NORSRAMCmd(FSMC_Bank1_NORSRAM3, ENABLE);
+*/
+}
+#endif /* DATA_IN_ExtSRAM */
+#endif /* STM32L151xD || STM32L152xD || STM32L162xD */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/hw/mcu/stm/stm32l1xx/syscfg.yml b/hw/mcu/stm/stm32l1xx/syscfg.yml
index 2bd68bb..86f7774 100644
--- a/hw/mcu/stm/stm32l1xx/syscfg.yml
+++ b/hw/mcu/stm/stm32l1xx/syscfg.yml
@@ -31,6 +31,78 @@ syscfg.defs:
         description: MCUs are of STM32L1xx family
         value: 1
 
+    STM32_CLOCK_VOLTAGESCALING_CONFIG:
+        description: Adjust voltage scale
+        value: 0
+
+    STM32_CLOCK_LSI:
+        description: Enable low-speed internal clock source
+        value: 0
+
+    STM32_CLOCK_LSE:
+        description: Enable low-speed external clock source (aka RTC xtal)
+        value: 0
+
+    STM32_CLOCK_LSE_BYPASS:
+        description: 0 for 32768 xtal; 1 for input clock
+        value: 0
+
+    STM32_CLOCK_MSI:
+        description: Enable multi-speed internal clock source
+        value: 1
+
+    STM32_CLOCK_MSI_CALIBRATION:
+        description: MSI calibration value
+        value: 'RCC_MSICALIBRATION_DEFAULT'
+
+    STM32_CLOCK_MSI_CLOCK_RANGE:
+        description: MSI clock range
+        value: 'RCC_MSIRANGE_5'
+
+    STM32_CLOCK_HSE:
+        description: Enable high-speed external clock source
+        value: 0
+
+    STM32_CLOCK_HSE_BYPASS:
+        description: 0 for xtal; 1 for input clock
+        value: 0
+
+    STM32_CLOCK_HSI:
+        description: Enable high-speed internal clock source
+        value: 1
+
+    STM32_CLOCK_HSI_CALIBRATION:
+        description: HSI calibration value
+        value: 'RCC_HSICALIBRATION_DEFAULT'
+
+    STM32_CLOCK_PLL_MUL:
+        description: PLL MUL parameter
+        value: 0
+
+    STM32_CLOCK_PLL_DIV:
+        description: PLL DIV parameter
+        value: 0
+
+    STM32_CLOCK_AHB_DIVIDER:
+        description: AHB CLK1 prescaler (64MHz max)
+        value: 0
+
+    STM32_CLOCK_APB1_DIVIDER:
+        description: APB low-speed prescaler (64MHz max)
+        value: 0
+
+    STM32_CLOCK_APB2_DIVIDER:
+        description: APB high-speed prescaler (64MHz max)
+        value: 0
+
+    STM32_FLASH_LATENCY:
+        description: Number of wait-states
+        value: 0
+
+    STM32_FLASH_PREFETCH_ENABLE:
+        description: Enable pre-fetch of instructions (when latency > 0)
+        value: 0
+
     STM32_HAL_SPI_HAS_FIFO:
         description: This MCU has a SPI without FIFO
         value: 0