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:46 UTC

[mynewt-core] 03/06: mcu: stm32l0: 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 ed505690f0b371a5d26801c68b28e41f061f35d6
Author: Fabio Utzig <ut...@apache.org>
AuthorDate: Fri Nov 29 08:27:41 2019 -0300

    mcu: stm32l0: update to syscfg based clock system
---
 .../include/bsp/stm32l0xx_hal_conf.h               |  73 +++---
 hw/bsp/b-l072z-lrwan1/src/system_stm32l0xx.c       | 276 ---------------------
 hw/bsp/b-l072z-lrwan1/syscfg.yml                   |  20 ++
 hw/mcu/stm/stm32l0xx/src/clock_stm32l0xx.c         | 266 ++++++++++++++++++++
 hw/mcu/stm/stm32l0xx/src/system_stm32l0xx.c        | 191 ++++++++++++++
 hw/mcu/stm/stm32l0xx/syscfg.yml                    |  76 ++++++
 6 files changed, 589 insertions(+), 313 deletions(-)

diff --git a/hw/bsp/b-l072z-lrwan1/include/bsp/stm32l0xx_hal_conf.h b/hw/bsp/b-l072z-lrwan1/include/bsp/stm32l0xx_hal_conf.h
index a718ddd..d3625e1 100644
--- a/hw/bsp/b-l072z-lrwan1/include/bsp/stm32l0xx_hal_conf.h
+++ b/hw/bsp/b-l072z-lrwan1/include/bsp/stm32l0xx_hal_conf.h
@@ -2,7 +2,7 @@
   ******************************************************************************
   * @file    stm32l0xx_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 __STM32L0xx_HAL_CONF_H
 #define __STM32L0xx_HAL_CONF_H
 
+#include <syscfg/syscfg.h>
+
 #ifdef __cplusplus
  extern "C" {
 #endif
@@ -49,28 +51,28 @@
   * @brief This is the list of modules to be used in the HAL driver 
   */
 #if 0
-#define HAL_MODULE_ENABLED  
-#define HAL_ADC_MODULE_ENABLED   
-#define HAL_COMP_MODULE_ENABLED 
-#define HAL_CRC_MODULE_ENABLED  
-#define HAL_CRYP_MODULE_ENABLED  
-#define HAL_DAC_MODULE_ENABLED   
+#define HAL_MODULE_ENABLED
+#define HAL_ADC_MODULE_ENABLED
+#define HAL_COMP_MODULE_ENABLED
+#define HAL_CRC_MODULE_ENABLED
+#define HAL_CRYP_MODULE_ENABLED
+#define HAL_DAC_MODULE_ENABLED
 /* #define HAL_FIREWALL_MODULE_ENABLED */
-#define HAL_I2S_MODULE_ENABLED   
-#define HAL_LCD_MODULE_ENABLED 
+#define HAL_I2S_MODULE_ENABLED
+#define HAL_LCD_MODULE_ENABLED
 #define HAL_LPTIM_MODULE_ENABLED
-#define HAL_RNG_MODULE_ENABLED   
+#define HAL_RNG_MODULE_ENABLED
 #define HAL_RTC_MODULE_ENABLED
 #define HAL_TIM_MODULE_ENABLED
-#define HAL_TSC_MODULE_ENABLED   
-#define HAL_UART_MODULE_ENABLED 
-#define HAL_USART_MODULE_ENABLED 
-#define HAL_IRDA_MODULE_ENABLED 
-#define HAL_SMARTCARD_MODULE_ENABLED 
-#define HAL_SMBUS_MODULE_ENABLED 
-#define HAL_WWDG_MODULE_ENABLED  
+#define HAL_TSC_MODULE_ENABLED
+#define HAL_UART_MODULE_ENABLED
+#define HAL_USART_MODULE_ENABLED
+#define HAL_IRDA_MODULE_ENABLED
+#define HAL_SMARTCARD_MODULE_ENABLED
+#define HAL_SMBUS_MODULE_ENABLED
+#define HAL_WWDG_MODULE_ENABLED
 #define HAL_CORTEX_MODULE_ENABLED
-#define HAL_PCD_MODULE_ENABLED 
+#define HAL_PCD_MODULE_ENABLED
 #endif
 
 #define HAL_FLASH_MODULE_ENABLED
@@ -88,7 +90,7 @@
   *        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).  
   */
-#if !defined  (HSE_VALUE) 
+#if !defined  (HSE_VALUE)
   #define HSE_VALUE    ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
 #endif /* HSE_VALUE */
 
@@ -101,12 +103,12 @@
   *        This value is the default MSI range value after Reset.
   */
 #if !defined  (MSI_VALUE)
-  #define MSI_VALUE    ((uint32_t)2000000U) /*!< Value of the Internal oscillator in Hz*/
+  #define MSI_VALUE    ((uint32_t)2097152U) /*!< Value of the Internal oscillator in Hz*/
 #endif /* MSI_VALUE */
 /**
   * @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    ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
@@ -115,7 +117,7 @@
 /**
   * @brief Internal High Speed oscillator for USB (HSI48) value.
   */
-#if !defined  (HSI48_VALUE) 
+#if !defined  (HSI48_VALUE)
 #define HSI48_VALUE ((uint32_t)48000000U) /*!< Value of the Internal High Speed oscillator for USB in Hz.
                                              The real value may vary depending on the variations
                                              in voltage and temperature.  */
@@ -144,37 +146,36 @@
   #define LSE_STARTUP_TIMEOUT    ((uint32_t)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                    ((uint32_t)3300U) /*!< Value of VDD in mv */
-#define  TICK_INT_PRIORITY            (((uint32_t)1U<<__NVIC_PRIO_BITS) - 1U)    /*!< tick interrupt priority */            
-#define  USE_RTOS                     0U     
-#define  PREFETCH_ENABLE              1U              
-#define  PREREAD_ENABLE               0U
-#define  BUFFER_CACHE_DISABLE         0U
+#define  TICK_INT_PRIORITY            (((uint32_t)1U<<__NVIC_PRIO_BITS) - 1U)    /*!< 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    1 */
 
 /* Includes ------------------------------------------------------------------*/
 /**
-  * @brief Include module's header file 
+  * @brief Include module's header file
   */
 
 #ifdef HAL_RCC_MODULE_ENABLED
   #include "stm32l0xx_hal_rcc.h"
 #endif /* HAL_RCC_MODULE_ENABLED */
-  
+
 #ifdef HAL_GPIO_MODULE_ENABLED
   #include "stm32l0xx_hal_gpio.h"
 #endif /* HAL_GPIO_MODULE_ENABLED */
@@ -214,7 +215,7 @@
 #ifdef HAL_FLASH_MODULE_ENABLED
   #include "stm32l0xx_hal_flash.h"
 #endif /* HAL_FLASH_MODULE_ENABLED */
- 
+
 #ifdef HAL_I2C_MODULE_ENABLED
  #include "stm32l0xx_hal_i2c.h"
 #endif /* HAL_I2C_MODULE_ENABLED */
@@ -234,7 +235,7 @@
 #ifdef HAL_LPTIM_MODULE_ENABLED
 #include "stm32l0xx_hal_lptim.h"
 #endif /* HAL_LPTIM_MODULE_ENABLED */
-   
+
 #ifdef HAL_PWR_MODULE_ENABLED
  #include "stm32l0xx_hal_pwr.h"
 #endif /* HAL_PWR_MODULE_ENABLED */
@@ -309,7 +310,5 @@
 #endif
 
 #endif /* __STM32L0xx_HAL_CONF_H */
- 
 
 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
-
diff --git a/hw/bsp/b-l072z-lrwan1/src/system_stm32l0xx.c b/hw/bsp/b-l072z-lrwan1/src/system_stm32l0xx.c
deleted file mode 100644
index 140fa11..0000000
--- a/hw/bsp/b-l072z-lrwan1/src/system_stm32l0xx.c
+++ /dev/null
@@ -1,276 +0,0 @@
-/**
-  ******************************************************************************
-  * @file    system_stm32l0xx.c
-  * @author  MCD Application Team
-  * @brief   CMSIS Cortex-M0+ 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_stm32l0xx.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) 2016 STMicroelectronics.
-  * All rights reserved.</center></h2>
-  *
-  * This software component is licensed by ST under BSD 3-Clause license,
-  * the "License"; You may not use this file except in compliance with the
-  * License. You may obtain a copy of the License at:
-  *                        opensource.org/licenses/BSD-3-Clause
-  *
-  ******************************************************************************
-  */
-
-/** @addtogroup CMSIS
-  * @{
-  */
-
-/** @addtogroup stm32l0xx_system
-  * @{
-  */
-
-/** @addtogroup STM32L0xx_System_Private_Includes
-  * @{
-  */
-
-#include "stm32l0xx.h"
-#include "mcu/cmsis_nvic.h"
-
-#if !defined  (HSE_VALUE)
-  #define HSE_VALUE    ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
-#endif /* HSE_VALUE */
-
-#if !defined  (MSI_VALUE)
-  #define MSI_VALUE    ((uint32_t)2097152U) /*!< Value of the Internal oscillator in Hz*/
-#endif /* MSI_VALUE */
-
-#if !defined  (HSI_VALUE)
-  #define HSI_VALUE    ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
-#endif /* HSI_VALUE */
-
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L0xx_System_Private_TypesDefinitions
-  * @{
-  */
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L0xx_System_Private_Defines
-  * @{
-  */
-/************************* Miscellaneous Configuration ************************/
-
-/*!< 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 0x100. */
-/******************************************************************************/
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L0xx_System_Private_Macros
-  * @{
-  */
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L0xx_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 = 2097152U; /* 32.768 kHz * 2^6 */
-  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};
-  const uint8_t PLLMulTable[9] = {3U, 4U, 6U, 8U, 12U, 16U, 24U, 32U, 48U};
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L0xx_System_Private_FunctionPrototypes
-  * @{
-  */
-
-/**
-  * @}
-  */
-
-/** @addtogroup STM32L0xx_System_Private_Functions
-  * @{
-  */
-
-/**
-  * @brief  Setup the microcontroller system.
-  * @param  None
-  * @retval None
-  */
-void SystemInit (void)
-{
-/*!< Set MSION bit */
-  RCC->CR |= (uint32_t)0x00000100U;
-
-  /*!< 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) 0x88FF400CU;
-
-  /*!< Reset HSION, HSIDIVEN, HSEON, CSSON and PLLON bits */
-  RCC->CR &= (uint32_t)0xFEF6FFF6U;
-
-  /*!< Reset HSI48ON  bit */
-  RCC->CRRCR &= (uint32_t)0xFFFFFFFEU;
-
-  /*!< Reset HSEBYP bit */
-  RCC->CR &= (uint32_t)0xFFFBFFFFU;
-
-  /*!< Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */
-  RCC->CFGR &= (uint32_t)0xFF02FFFFU;
-
-  /*!< Disable all interrupts */
-  RCC->CIER = 0x00000000U;
-
-  /* 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 stm32l0xx_hal.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 stm32l0xx_hal.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 = 0U, pllmul = 0U, plldiv = 0U, pllsource = 0U, msirange = 0U;
-
-  /* Get SYSCLK source -------------------------------------------------------*/
-  tmp = RCC->CFGR & RCC_CFGR_SWS;
-
-  switch (tmp)
-  {
-    case 0x00U:  /* MSI used as system clock */
-      msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> RCC_ICSCR_MSIRANGE_Pos;
-      SystemCoreClock = (32768U * (1U << (msirange + 1U)));
-      break;
-    case 0x04U:  /* HSI used as system clock */
-      if ((RCC->CR & RCC_CR_HSIDIVF) != 0U)
-      {
-        SystemCoreClock = HSI_VALUE / 4U;
-      }
-      else
-      {
-        SystemCoreClock = HSI_VALUE;
-      }
-      break;
-    case 0x08U:  /* HSE used as system clock */
-      SystemCoreClock = HSE_VALUE;
-      break;
-    default:  /* 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 >> RCC_CFGR_PLLMUL_Pos)];
-      plldiv = (plldiv >> RCC_CFGR_PLLDIV_Pos) + 1U;
-
-      pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
-
-      if (pllsource == 0x00U)
-      {
-        /* HSI oscillator clock selected as PLL clock entry */
-        if ((RCC->CR & RCC_CR_HSIDIVF) != 0U)
-        {
-          SystemCoreClock = (((HSI_VALUE / 4U) * pllmul) / plldiv);
-        }
-        else
-        {
-          SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv);
-        }
-      }
-      else
-      {
-        /* HSE selected as PLL clock entry */
-        SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv);
-      }
-      break;
-  }
-  /* Compute HCLK clock frequency --------------------------------------------*/
-  /* Get HCLK prescaler */
-  tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos)];
-  /* HCLK clock frequency */
-  SystemCoreClock >>= tmp;
-}
-
-
-
-/**
-  * @}
-  */
-
-/**
-  * @}
-  */
-
-/**
-  * @}
-  */
-
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/hw/bsp/b-l072z-lrwan1/syscfg.yml b/hw/bsp/b-l072z-lrwan1/syscfg.yml
index 6344c10..28c3915 100644
--- a/hw/bsp/b-l072z-lrwan1/syscfg.yml
+++ b/hw/bsp/b-l072z-lrwan1/syscfg.yml
@@ -43,3 +43,23 @@ syscfg.vals:
     CONFIG_FCB_FLASH_AREA: FLASH_AREA_NFFS
     NFFS_FLASH_AREA: FLASH_AREA_NFFS
     COREDUMP_FLASH_AREA: FLASH_AREA_IMAGE_1
+    SX1276_SPI_IDX: 0
+    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_HSI48: 0
+    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/stm32l0xx/src/clock_stm32l0xx.c b/hw/mcu/stm/stm32l0xx/src/clock_stm32l0xx.c
new file mode 100644
index 0000000..f87536f
--- /dev/null
+++ b/hw/mcu/stm/stm32l0xx/src/clock_stm32l0xx.c
@@ -0,0 +1,266 @@
+/*
+ * <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 "stm32l0xx_hal_pwr_ex.h"
+#include "stm32l0xx_hal_rcc.h"
+#include "stm32l0xx_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) || MYNEWT_VAL(STM32_CLOCK_HSI48)
+
+/*
+ * 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
+
+#if MYNEWT_VAL(STM32_CLOCK_HSI48) && !defined(RCC_HSI48_SUPPORT)
+#error "HSI48 not supported on this target"
+#endif
+
+#if MYNEWT_VAL(STM32_CLOCK_HSI48)
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_HSI48;
+    osc_init.HSI48State = RCC_HSI48_ON;
+#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_HSI48) == 0) || (MYNEWT_VAL(STM32_CLOCK_MSI) == 0))
+    /*
+     * Turn off HSE/HSI/HSI48 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_HSI48) == 0) && defined(RCC_HSI48_SUPPORT)
+    osc_init.OscillatorType |= RCC_OSCILLATORTYPE_HSI48;
+    osc_init.HSI48State = RCC_HSI48_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/stm32l0xx/src/system_stm32l0xx.c b/hw/mcu/stm/stm32l0xx/src/system_stm32l0xx.c
new file mode 100644
index 0000000..97c4765
--- /dev/null
+++ b/hw/mcu/stm/stm32l0xx/src/system_stm32l0xx.c
@@ -0,0 +1,191 @@
+/**
+  * <h2><center>&copy; Copyright(c) 2016 STMicroelectronics.
+  * All rights reserved.</center></h2>
+  *
+  * This software component is licensed by ST under BSD 3-Clause license,
+  * the "License"; You may not use this file except in compliance with the
+  * License. You may obtain a copy of the License at:
+  *                        opensource.org/licenses/BSD-3-Clause
+  */
+
+#include <stdint.h>
+#include "bsp/stm32l0xx_hal_conf.h"
+#include "stm32l0xx.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 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
+};
+const uint8_t PLLMulTable[9] = {
+    3U, 4U, 6U, 8U, 12U, 16U, 24U, 32U, 48U
+};
+
+/*
+ * XXX BSP specific
+ */
+void SystemClock_Config(void);
+
+/**
+  * @brief  Setup the microcontroller system.
+  * @param  None
+  * @retval None
+  */
+void
+SystemInit(void)
+{
+    /* Set MSION bit */
+    RCC->CR |= (uint32_t)0x00000100U;
+
+    /*
+     * 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) 0x88FF400CU;
+
+    /* Reset HSION, HSIDIVEN, HSEON, CSSON and PLLON bits */
+    RCC->CR &= (uint32_t)0xFEF6FFF6U;
+
+    /* Reset HSI48ON  bit */
+    RCC->CRRCR &= (uint32_t)0xFFFFFFFEU;
+
+    /* Reset HSEBYP bit */
+    RCC->CR &= (uint32_t)0xFFFBFFFFU;
+
+    /* Reset PLLSRC, PLLMUL[3:0] and PLLDIV[1:0] bits */
+    RCC->CFGR &= (uint32_t)0xFF02FFFFU;
+
+    /* Disable all interrupts */
+    RCC->CIER = 0x00000000U;
+
+    /* 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 stm32l0xx_hal.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 stm32l0xx_hal.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) {
+    /* MSI used as system clock */
+    case 0x00U:
+        msirange = (RCC->ICSCR & RCC_ICSCR_MSIRANGE) >> RCC_ICSCR_MSIRANGE_Pos;
+        SystemCoreClock = (32768U * (1U << (msirange + 1U)));
+        break;
+
+    /* HSI used as system clock */
+    case 0x04U:
+        if ((RCC->CR & RCC_CR_HSIDIVF) != 0U) {
+            SystemCoreClock = HSI_VALUE / 4U;
+        } else {
+            SystemCoreClock = HSI_VALUE;
+        }
+        break;
+
+    /* HSE used as system clock */
+    case 0x08U:
+        SystemCoreClock = HSE_VALUE;
+        break;
+
+    /* PLL used as system clock */
+    default:
+        /*
+         * Get PLL clock source and multiplication factor
+         */
+        pllmul = RCC->CFGR & RCC_CFGR_PLLMUL;
+        plldiv = RCC->CFGR & RCC_CFGR_PLLDIV;
+        pllmul = PLLMulTable[(pllmul >> RCC_CFGR_PLLMUL_Pos)];
+        plldiv = (plldiv >> RCC_CFGR_PLLDIV_Pos) + 1U;
+
+        pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+
+        if (pllsource == 0x00U) {
+            /* HSI oscillator clock selected as PLL clock entry */
+            if ((RCC->CR & RCC_CR_HSIDIVF) != 0U) {
+                SystemCoreClock = (((HSI_VALUE / 4U) * pllmul) / plldiv);
+            } else {
+                SystemCoreClock = (((HSI_VALUE) * pllmul) / plldiv);
+            }
+        } else {
+            /* HSE selected as PLL clock entry */
+            SystemCoreClock = (((HSE_VALUE) * pllmul) / plldiv);
+        }
+        break;
+    }
+
+    /*
+     * Compute HCLK clock frequency
+     */
+
+    /* Get HCLK prescaler */
+    tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos)];
+
+    /* HCLK clock frequency */
+    SystemCoreClock >>= tmp;
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/hw/mcu/stm/stm32l0xx/syscfg.yml b/hw/mcu/stm/stm32l0xx/syscfg.yml
index b0db2ec..4ad28f1 100644
--- a/hw/mcu/stm/stm32l0xx/syscfg.yml
+++ b/hw/mcu/stm/stm32l0xx/syscfg.yml
@@ -31,6 +31,82 @@ syscfg.defs:
         description: MCUs are of STM32L0xx 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_HSI48:
+        description: Enable high-speed 48MHz internal clock source
+        value: 0
+
+    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