summaryrefslogtreecommitdiff
path: root/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src
diff options
context:
space:
mode:
Diffstat (limited to 'FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src')
-rw-r--r--FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/main.c710
-rw-r--r--FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_msp.c562
-rw-r--r--FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_timebase_tim.c114
-rw-r--r--FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_it.c200
-rw-r--r--FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/system_stm32l4xx.c337
5 files changed, 1923 insertions, 0 deletions
diff --git a/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/main.c b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/main.c
new file mode 100644
index 000000000..cfeb512e3
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/main.c
@@ -0,0 +1,710 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file : main.c
+ * @brief : Main program body
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; Copyright (c) 2019 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
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+#include "app_main.h"
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN PTD */
+
+/* USER CODE END PTD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+DFSDM_Channel_HandleTypeDef hdfsdm1_channel1;
+
+I2C_HandleTypeDef hi2c2;
+
+QSPI_HandleTypeDef hqspi;
+
+SPI_HandleTypeDef hspi3;
+
+UART_HandleTypeDef huart1;
+UART_HandleTypeDef huart3;
+
+PCD_HandleTypeDef hpcd_USB_OTG_FS;
+
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+void SystemClock_Config(void);
+static void MX_GPIO_Init(void);
+static void MX_DFSDM1_Init(void);
+static void MX_I2C2_Init(void);
+static void MX_QUADSPI_Init(void);
+static void MX_SPI3_Init(void);
+static void MX_USART1_UART_Init(void);
+static void MX_USART3_UART_Init(void);
+static void MX_USB_OTG_FS_PCD_Init(void);
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/**
+ * @brief The application entry point.
+ * @retval int
+ */
+int main(void)
+{
+ /* USER CODE BEGIN 1 */
+
+ /* USER CODE END 1 */
+
+
+ /* MCU Configuration--------------------------------------------------------*/
+
+ /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
+ HAL_Init();
+
+ /* USER CODE BEGIN Init */
+
+ /* USER CODE END Init */
+
+ /* Configure the system clock */
+ SystemClock_Config();
+
+ /* USER CODE BEGIN SysInit */
+
+ /* USER CODE END SysInit */
+
+ /* Initialize all configured peripherals */
+ MX_GPIO_Init();
+ MX_DFSDM1_Init();
+ MX_I2C2_Init();
+ MX_QUADSPI_Init();
+ MX_SPI3_Init();
+ MX_USART1_UART_Init();
+ MX_USART3_UART_Init();
+ MX_USB_OTG_FS_PCD_Init();
+ /* USER CODE BEGIN 2 */
+ /* Call our entry point. */
+ app_main();
+ /* USER CODE END 2 */
+
+ /* Infinite loop */
+ /* USER CODE BEGIN WHILE */
+ while (1)
+ {
+ /* USER CODE END WHILE */
+
+ /* USER CODE BEGIN 3 */
+ }
+ /* USER CODE END 3 */
+}
+
+/**
+ * @brief System Clock Configuration
+ * @retval None
+ */
+void SystemClock_Config(void)
+{
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
+ RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
+
+ /** Configure LSE Drive Capability
+ */
+ HAL_PWR_EnableBkUpAccess();
+ __HAL_RCC_LSEDRIVE_CONFIG(RCC_LSEDRIVE_LOW);
+ /** Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE|RCC_OSCILLATORTYPE_MSI;
+ RCC_OscInitStruct.LSEState = RCC_LSE_ON;
+ RCC_OscInitStruct.MSIState = RCC_MSI_ON;
+ RCC_OscInitStruct.MSICalibrationValue = 0;
+ RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_6;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
+ RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI;
+ RCC_OscInitStruct.PLL.PLLM = 1;
+ RCC_OscInitStruct.PLL.PLLN = 40;
+ RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV7;
+ RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
+ RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Initializes the CPU, AHB and APB busses clocks
+ */
+ RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
+ |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_4) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART3
+ |RCC_PERIPHCLK_I2C2|RCC_PERIPHCLK_DFSDM1
+ |RCC_PERIPHCLK_USB;
+ PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
+ PeriphClkInit.Usart3ClockSelection = RCC_USART3CLKSOURCE_PCLK1;
+ PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1;
+ PeriphClkInit.Dfsdm1ClockSelection = RCC_DFSDM1CLKSOURCE_PCLK;
+ PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_PLLSAI1;
+ PeriphClkInit.PLLSAI1.PLLSAI1Source = RCC_PLLSOURCE_MSI;
+ PeriphClkInit.PLLSAI1.PLLSAI1M = 1;
+ PeriphClkInit.PLLSAI1.PLLSAI1N = 24;
+ PeriphClkInit.PLLSAI1.PLLSAI1P = RCC_PLLP_DIV7;
+ PeriphClkInit.PLLSAI1.PLLSAI1Q = RCC_PLLQ_DIV2;
+ PeriphClkInit.PLLSAI1.PLLSAI1R = RCC_PLLR_DIV2;
+ PeriphClkInit.PLLSAI1.PLLSAI1ClockOut = RCC_PLLSAI1_48M2CLK;
+ if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Configure the main internal regulator output voltage
+ */
+ if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Enable MSI Auto calibration
+ */
+ HAL_RCCEx_EnableMSIPLLMode();
+}
+
+/**
+ * @brief DFSDM1 Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_DFSDM1_Init(void)
+{
+
+ /* USER CODE BEGIN DFSDM1_Init 0 */
+
+ /* USER CODE END DFSDM1_Init 0 */
+
+ /* USER CODE BEGIN DFSDM1_Init 1 */
+
+ /* USER CODE END DFSDM1_Init 1 */
+ hdfsdm1_channel1.Instance = DFSDM1_Channel1;
+ hdfsdm1_channel1.Init.OutputClock.Activation = ENABLE;
+ hdfsdm1_channel1.Init.OutputClock.Selection = DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM;
+ hdfsdm1_channel1.Init.OutputClock.Divider = 2;
+ hdfsdm1_channel1.Init.Input.Multiplexer = DFSDM_CHANNEL_EXTERNAL_INPUTS;
+ hdfsdm1_channel1.Init.Input.DataPacking = DFSDM_CHANNEL_STANDARD_MODE;
+ hdfsdm1_channel1.Init.Input.Pins = DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS;
+ hdfsdm1_channel1.Init.SerialInterface.Type = DFSDM_CHANNEL_SPI_RISING;
+ hdfsdm1_channel1.Init.SerialInterface.SpiClock = DFSDM_CHANNEL_SPI_CLOCK_INTERNAL;
+ hdfsdm1_channel1.Init.Awd.FilterOrder = DFSDM_CHANNEL_FASTSINC_ORDER;
+ hdfsdm1_channel1.Init.Awd.Oversampling = 1;
+ hdfsdm1_channel1.Init.Offset = 0;
+ hdfsdm1_channel1.Init.RightBitShift = 0x00;
+ if (HAL_DFSDM_ChannelInit(&hdfsdm1_channel1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN DFSDM1_Init 2 */
+
+ /* USER CODE END DFSDM1_Init 2 */
+
+}
+
+/**
+ * @brief I2C2 Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_I2C2_Init(void)
+{
+
+ /* USER CODE BEGIN I2C2_Init 0 */
+
+ /* USER CODE END I2C2_Init 0 */
+
+ /* USER CODE BEGIN I2C2_Init 1 */
+
+ /* USER CODE END I2C2_Init 1 */
+ hi2c2.Instance = I2C2;
+ hi2c2.Init.Timing = 0x10909CEC;
+ hi2c2.Init.OwnAddress1 = 0;
+ hi2c2.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
+ hi2c2.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
+ hi2c2.Init.OwnAddress2 = 0;
+ hi2c2.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
+ hi2c2.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
+ hi2c2.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
+ if (HAL_I2C_Init(&hi2c2) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Configure Analogue filter
+ */
+ if (HAL_I2CEx_ConfigAnalogFilter(&hi2c2, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /** Configure Digital filter
+ */
+ if (HAL_I2CEx_ConfigDigitalFilter(&hi2c2, 0) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN I2C2_Init 2 */
+
+ /* USER CODE END I2C2_Init 2 */
+
+}
+
+/**
+ * @brief QUADSPI Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_QUADSPI_Init(void)
+{
+
+ /* USER CODE BEGIN QUADSPI_Init 0 */
+
+ /* USER CODE END QUADSPI_Init 0 */
+
+ /* USER CODE BEGIN QUADSPI_Init 1 */
+
+ /* USER CODE END QUADSPI_Init 1 */
+ /* QUADSPI parameter configuration*/
+ hqspi.Instance = QUADSPI;
+ hqspi.Init.ClockPrescaler = 255;
+ hqspi.Init.FifoThreshold = 1;
+ hqspi.Init.SampleShifting = QSPI_SAMPLE_SHIFTING_NONE;
+ hqspi.Init.FlashSize = 1;
+ hqspi.Init.ChipSelectHighTime = QSPI_CS_HIGH_TIME_1_CYCLE;
+ hqspi.Init.ClockMode = QSPI_CLOCK_MODE_0;
+ if (HAL_QSPI_Init(&hqspi) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN QUADSPI_Init 2 */
+
+ /* USER CODE END QUADSPI_Init 2 */
+
+}
+
+/**
+ * @brief SPI3 Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_SPI3_Init(void)
+{
+
+ /* USER CODE BEGIN SPI3_Init 0 */
+
+ /* USER CODE END SPI3_Init 0 */
+
+ /* USER CODE BEGIN SPI3_Init 1 */
+
+ /* USER CODE END SPI3_Init 1 */
+ /* SPI3 parameter configuration*/
+ hspi3.Instance = SPI3;
+ hspi3.Init.Mode = SPI_MODE_MASTER;
+ hspi3.Init.Direction = SPI_DIRECTION_2LINES;
+ hspi3.Init.DataSize = SPI_DATASIZE_4BIT;
+ hspi3.Init.CLKPolarity = SPI_POLARITY_LOW;
+ hspi3.Init.CLKPhase = SPI_PHASE_1EDGE;
+ hspi3.Init.NSS = SPI_NSS_SOFT;
+ hspi3.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
+ hspi3.Init.FirstBit = SPI_FIRSTBIT_MSB;
+ hspi3.Init.TIMode = SPI_TIMODE_DISABLE;
+ hspi3.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
+ hspi3.Init.CRCPolynomial = 7;
+ hspi3.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
+ hspi3.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
+ if (HAL_SPI_Init(&hspi3) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN SPI3_Init 2 */
+
+ /* USER CODE END SPI3_Init 2 */
+
+}
+
+/**
+ * @brief USART1 Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_USART1_UART_Init(void)
+{
+
+ /* USER CODE BEGIN USART1_Init 0 */
+
+ /* USER CODE END USART1_Init 0 */
+
+ /* USER CODE BEGIN USART1_Init 1 */
+
+ /* USER CODE END USART1_Init 1 */
+ huart1.Instance = USART1;
+ huart1.Init.BaudRate = 115200;
+ huart1.Init.WordLength = UART_WORDLENGTH_8B;
+ huart1.Init.StopBits = UART_STOPBITS_1;
+ huart1.Init.Parity = UART_PARITY_NONE;
+ huart1.Init.Mode = UART_MODE_TX_RX;
+ huart1.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart1.Init.OverSampling = UART_OVERSAMPLING_16;
+ huart1.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
+ huart1.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
+ if (HAL_UART_Init(&huart1) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN USART1_Init 2 */
+
+ /* USER CODE END USART1_Init 2 */
+
+}
+
+/**
+ * @brief USART3 Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_USART3_UART_Init(void)
+{
+
+ /* USER CODE BEGIN USART3_Init 0 */
+
+ /* USER CODE END USART3_Init 0 */
+
+ /* USER CODE BEGIN USART3_Init 1 */
+
+ /* USER CODE END USART3_Init 1 */
+ huart3.Instance = USART3;
+ huart3.Init.BaudRate = 115200;
+ huart3.Init.WordLength = UART_WORDLENGTH_8B;
+ huart3.Init.StopBits = UART_STOPBITS_1;
+ huart3.Init.Parity = UART_PARITY_NONE;
+ huart3.Init.Mode = UART_MODE_TX_RX;
+ huart3.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart3.Init.OverSampling = UART_OVERSAMPLING_16;
+ huart3.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
+ huart3.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
+ if (HAL_UART_Init(&huart3) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN USART3_Init 2 */
+
+ /* USER CODE END USART3_Init 2 */
+
+}
+
+/**
+ * @brief USB_OTG_FS Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_USB_OTG_FS_PCD_Init(void)
+{
+
+ /* USER CODE BEGIN USB_OTG_FS_Init 0 */
+
+ /* USER CODE END USB_OTG_FS_Init 0 */
+
+ /* USER CODE BEGIN USB_OTG_FS_Init 1 */
+
+ /* USER CODE END USB_OTG_FS_Init 1 */
+ hpcd_USB_OTG_FS.Instance = USB_OTG_FS;
+ hpcd_USB_OTG_FS.Init.dev_endpoints = 6;
+ hpcd_USB_OTG_FS.Init.speed = PCD_SPEED_FULL;
+ hpcd_USB_OTG_FS.Init.phy_itface = PCD_PHY_EMBEDDED;
+ hpcd_USB_OTG_FS.Init.Sof_enable = DISABLE;
+ hpcd_USB_OTG_FS.Init.low_power_enable = DISABLE;
+ hpcd_USB_OTG_FS.Init.lpm_enable = DISABLE;
+ hpcd_USB_OTG_FS.Init.battery_charging_enable = DISABLE;
+ hpcd_USB_OTG_FS.Init.use_dedicated_ep1 = DISABLE;
+ hpcd_USB_OTG_FS.Init.vbus_sensing_enable = DISABLE;
+ if (HAL_PCD_Init(&hpcd_USB_OTG_FS) != HAL_OK)
+ {
+ Error_Handler();
+ }
+ /* USER CODE BEGIN USB_OTG_FS_Init 2 */
+
+ /* USER CODE END USB_OTG_FS_Init 2 */
+
+}
+
+/**
+ * @brief GPIO Initialization Function
+ * @param None
+ * @retval None
+ */
+static void MX_GPIO_Init(void)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+
+ /* GPIO Ports Clock Enable */
+ __HAL_RCC_GPIOE_CLK_ENABLE();
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ __HAL_RCC_GPIOD_CLK_ENABLE();
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(GPIOE, M24SR64_Y_RF_DISABLE_Pin|M24SR64_Y_GPO_Pin|ISM43362_RST_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(GPIOA, ARD_D10_Pin|SPBTLE_RF_RST_Pin|ARD_D9_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(GPIOB, ARD_D8_Pin|ISM43362_BOOT0_Pin|ISM43362_WAKEUP_Pin|LED2_Pin
+ |SPSGRF_915_SDN_Pin|ARD_D5_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(GPIOD, USB_OTG_FS_PWR_EN_Pin|PMOD_RESET_Pin|STSAFE_A100_RESET_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(SPBTLE_RF_SPI3_CSN_GPIO_Port, SPBTLE_RF_SPI3_CSN_Pin, GPIO_PIN_SET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(GPIOC, VL53L0X_XSHUT_Pin|LED3_WIFI__LED4_BLE_Pin, GPIO_PIN_RESET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(SPSGRF_915_SPI3_CSN_GPIO_Port, SPSGRF_915_SPI3_CSN_Pin, GPIO_PIN_SET);
+
+ /*Configure GPIO pin Output Level */
+ HAL_GPIO_WritePin(ISM43362_SPI3_CSN_GPIO_Port, ISM43362_SPI3_CSN_Pin, GPIO_PIN_SET);
+
+ /*Configure GPIO pins : M24SR64_Y_RF_DISABLE_Pin M24SR64_Y_GPO_Pin ISM43362_RST_Pin ISM43362_SPI3_CSN_Pin */
+ GPIO_InitStruct.Pin = M24SR64_Y_RF_DISABLE_Pin|M24SR64_Y_GPO_Pin|ISM43362_RST_Pin|ISM43362_SPI3_CSN_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : USB_OTG_FS_OVRCR_EXTI3_Pin SPSGRF_915_GPIO3_EXTI5_Pin SPBTLE_RF_IRQ_EXTI6_Pin ISM43362_DRDY_EXTI1_Pin */
+ GPIO_InitStruct.Pin = USB_OTG_FS_OVRCR_EXTI3_Pin|SPSGRF_915_GPIO3_EXTI5_Pin|SPBTLE_RF_IRQ_EXTI6_Pin|ISM43362_DRDY_EXTI1_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : BUTTON_EXTI13_Pin */
+ GPIO_InitStruct.Pin = BUTTON_EXTI13_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(BUTTON_EXTI13_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : ARD_A5_Pin ARD_A4_Pin ARD_A3_Pin ARD_A2_Pin
+ ARD_A1_Pin ARD_A0_Pin */
+ GPIO_InitStruct.Pin = ARD_A5_Pin|ARD_A4_Pin|ARD_A3_Pin|ARD_A2_Pin
+ |ARD_A1_Pin|ARD_A0_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : ARD_D1_Pin ARD_D0_Pin */
+ GPIO_InitStruct.Pin = ARD_D1_Pin|ARD_D0_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF8_UART4;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : ARD_D10_Pin SPBTLE_RF_RST_Pin ARD_D9_Pin */
+ GPIO_InitStruct.Pin = ARD_D10_Pin|SPBTLE_RF_RST_Pin|ARD_D9_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : ARD_D4_Pin */
+ GPIO_InitStruct.Pin = ARD_D4_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF1_TIM2;
+ HAL_GPIO_Init(ARD_D4_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : ARD_D7_Pin */
+ GPIO_InitStruct.Pin = ARD_D7_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(ARD_D7_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : ARD_D13_Pin ARD_D12_Pin ARD_D11_Pin */
+ GPIO_InitStruct.Pin = ARD_D13_Pin|ARD_D12_Pin|ARD_D11_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF5_SPI1;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : ARD_D3_Pin */
+ GPIO_InitStruct.Pin = ARD_D3_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(ARD_D3_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : ARD_D6_Pin */
+ GPIO_InitStruct.Pin = ARD_D6_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_ANALOG_ADC_CONTROL;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(ARD_D6_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : ARD_D8_Pin ISM43362_BOOT0_Pin ISM43362_WAKEUP_Pin LED2_Pin
+ SPSGRF_915_SDN_Pin ARD_D5_Pin SPSGRF_915_SPI3_CSN_Pin */
+ GPIO_InitStruct.Pin = ARD_D8_Pin|ISM43362_BOOT0_Pin|ISM43362_WAKEUP_Pin|LED2_Pin
+ |SPSGRF_915_SDN_Pin|ARD_D5_Pin|SPSGRF_915_SPI3_CSN_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : LPS22HB_INT_DRDY_EXTI0_Pin LSM6DSL_INT1_EXTI11_Pin ARD_D2_Pin HTS221_DRDY_EXTI15_Pin
+ PMOD_IRQ_EXTI12_Pin */
+ GPIO_InitStruct.Pin = LPS22HB_INT_DRDY_EXTI0_Pin|LSM6DSL_INT1_EXTI11_Pin|ARD_D2_Pin|HTS221_DRDY_EXTI15_Pin
+ |PMOD_IRQ_EXTI12_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : USB_OTG_FS_PWR_EN_Pin SPBTLE_RF_SPI3_CSN_Pin PMOD_RESET_Pin STSAFE_A100_RESET_Pin */
+ GPIO_InitStruct.Pin = USB_OTG_FS_PWR_EN_Pin|SPBTLE_RF_SPI3_CSN_Pin|PMOD_RESET_Pin|STSAFE_A100_RESET_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : VL53L0X_XSHUT_Pin LED3_WIFI__LED4_BLE_Pin */
+ GPIO_InitStruct.Pin = VL53L0X_XSHUT_Pin|LED3_WIFI__LED4_BLE_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : VL53L0X_GPIO1_EXTI7_Pin LSM3MDL_DRDY_EXTI8_Pin */
+ GPIO_InitStruct.Pin = VL53L0X_GPIO1_EXTI7_Pin|LSM3MDL_DRDY_EXTI8_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ /*Configure GPIO pin : PMOD_SPI2_SCK_Pin */
+ GPIO_InitStruct.Pin = PMOD_SPI2_SCK_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
+ HAL_GPIO_Init(PMOD_SPI2_SCK_GPIO_Port, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : PMOD_UART2_CTS_Pin PMOD_UART2_RTS_Pin PMOD_UART2_TX_Pin PMOD_UART2_RX_Pin */
+ GPIO_InitStruct.Pin = PMOD_UART2_CTS_Pin|PMOD_UART2_RTS_Pin|PMOD_UART2_TX_Pin|PMOD_UART2_RX_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF7_USART2;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+
+ /*Configure GPIO pins : ARD_D15_Pin ARD_D14_Pin */
+ GPIO_InitStruct.Pin = ARD_D15_Pin|ARD_D14_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
+ GPIO_InitStruct.Pull = GPIO_PULLUP;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* EXTI interrupt init*/
+ HAL_NVIC_SetPriority(EXTI9_5_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(EXTI9_5_IRQn);
+
+ HAL_NVIC_SetPriority(EXTI15_10_IRQn, 0, 0);
+ HAL_NVIC_EnableIRQ(EXTI15_10_IRQn);
+
+}
+
+/* USER CODE BEGIN 4 */
+
+/* USER CODE END 4 */
+
+/**
+ * @brief Period elapsed callback in non blocking mode
+ * @note This function is called when TIM6 interrupt took place, inside
+ * HAL_TIM_IRQHandler(). It makes a direct call to HAL_IncTick() to increment
+ * a global variable "uwTick" used as application time base.
+ * @param htim : TIM handle
+ * @retval None
+ */
+void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim)
+{
+ /* USER CODE BEGIN Callback 0 */
+
+ /* USER CODE END Callback 0 */
+ if (htim->Instance == TIM6) {
+ HAL_IncTick();
+ }
+ /* USER CODE BEGIN Callback 1 */
+
+ /* USER CODE END Callback 1 */
+}
+
+/**
+ * @brief This function is executed in case of error occurrence.
+ * @retval None
+ */
+void Error_Handler(void)
+{
+ /* USER CODE BEGIN Error_Handler_Debug */
+ /* User can add his own implementation to report the HAL error return state */
+
+ /* USER CODE END Error_Handler_Debug */
+}
+
+#ifdef USE_FULL_ASSERT
+/**
+ * @brief Reports the name of the source file and the source line number
+ * where the assert_param error has occurred.
+ * @param file: pointer to the source file name
+ * @param line: assert_param error line source number
+ * @retval None
+ */
+void assert_failed(char *file, uint32_t line)
+{
+ /* USER CODE BEGIN 6 */
+ /* User can add his own implementation to report the file name and line number,
+ tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
+ /* USER CODE END 6 */
+}
+#endif /* USE_FULL_ASSERT */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_msp.c b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_msp.c
new file mode 100644
index 000000000..a8cea7ad6
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_msp.c
@@ -0,0 +1,562 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * File Name : stm32l4xx_hal_msp.c
+ * Description : This file provides code for the MSP Initialization
+ * and de-Initialization codes.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; Copyright (c) 2019 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
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+/* USER CODE BEGIN Includes */
+
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN Define */
+
+/* USER CODE END Define */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN Macro */
+
+/* USER CODE END Macro */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* External functions --------------------------------------------------------*/
+/* USER CODE BEGIN ExternalFunctions */
+
+/* USER CODE END ExternalFunctions */
+
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+/**
+ * Initializes the Global MSP.
+ */
+void HAL_MspInit(void)
+{
+ /* USER CODE BEGIN MspInit 0 */
+
+ /* USER CODE END MspInit 0 */
+
+ __HAL_RCC_SYSCFG_CLK_ENABLE();
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ /* System interrupt init*/
+
+ /* USER CODE BEGIN MspInit 1 */
+
+ /* USER CODE END MspInit 1 */
+}
+
+static uint32_t DFSDM1_Init = 0;
+/**
+* @brief DFSDM_Channel MSP Initialization
+* This function configures the hardware resources used in this example
+* @param hdfsdm_channel: DFSDM_Channel handle pointer
+* @retval None
+*/
+void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef* hdfsdm_channel)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(DFSDM1_Init == 0)
+ {
+ /* USER CODE BEGIN DFSDM1_MspInit 0 */
+
+ /* USER CODE END DFSDM1_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_DFSDM1_CLK_ENABLE();
+
+ __HAL_RCC_GPIOE_CLK_ENABLE();
+ /**DFSDM1 GPIO Configuration
+ PE7 ------> DFSDM1_DATIN2
+ PE9 ------> DFSDM1_CKOUT
+ */
+ GPIO_InitStruct.Pin = DFSDM1_DATIN2_Pin|DFSDM1_CKOUT_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
+ GPIO_InitStruct.Alternate = GPIO_AF6_DFSDM1;
+ HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN DFSDM1_MspInit 1 */
+
+ /* USER CODE END DFSDM1_MspInit 1 */
+ }
+
+}
+
+/**
+* @brief DFSDM_Channel MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param hdfsdm_channel: DFSDM_Channel handle pointer
+* @retval None
+*/
+void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef* hdfsdm_channel)
+{
+ DFSDM1_Init-- ;
+ if(DFSDM1_Init == 0)
+ {
+ /* USER CODE BEGIN DFSDM1_MspDeInit 0 */
+
+ /* USER CODE END DFSDM1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_DFSDM1_CLK_DISABLE();
+
+ /**DFSDM1 GPIO Configuration
+ PE7 ------> DFSDM1_DATIN2
+ PE9 ------> DFSDM1_CKOUT
+ */
+ HAL_GPIO_DeInit(GPIOE, DFSDM1_DATIN2_Pin|DFSDM1_CKOUT_Pin);
+
+ /* USER CODE BEGIN DFSDM1_MspDeInit 1 */
+
+ /* USER CODE END DFSDM1_MspDeInit 1 */
+ }
+
+}
+
+/**
+* @brief I2C MSP Initialization
+* This function configures the hardware resources used in this example
+* @param hi2c: I2C handle pointer
+* @retval None
+*/
+void HAL_I2C_MspInit(I2C_HandleTypeDef* hi2c)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(hi2c->Instance==I2C2)
+ {
+ /* USER CODE BEGIN I2C2_MspInit 0 */
+
+ /* USER CODE END I2C2_MspInit 0 */
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**I2C2 GPIO Configuration
+ PB10 ------> I2C2_SCL
+ PB11 ------> I2C2_SDA
+ */
+ GPIO_InitStruct.Pin = INTERNAL_I2C2_SCL_Pin|INTERNAL_I2C2_SDA_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
+ GPIO_InitStruct.Pull = GPIO_PULLUP;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF4_I2C2;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* Peripheral clock enable */
+ __HAL_RCC_I2C2_CLK_ENABLE();
+ /* USER CODE BEGIN I2C2_MspInit 1 */
+
+ /* USER CODE END I2C2_MspInit 1 */
+ }
+
+}
+
+/**
+* @brief I2C MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param hi2c: I2C handle pointer
+* @retval None
+*/
+void HAL_I2C_MspDeInit(I2C_HandleTypeDef* hi2c)
+{
+ if(hi2c->Instance==I2C2)
+ {
+ /* USER CODE BEGIN I2C2_MspDeInit 0 */
+
+ /* USER CODE END I2C2_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_I2C2_CLK_DISABLE();
+
+ /**I2C2 GPIO Configuration
+ PB10 ------> I2C2_SCL
+ PB11 ------> I2C2_SDA
+ */
+ HAL_GPIO_DeInit(GPIOB, INTERNAL_I2C2_SCL_Pin|INTERNAL_I2C2_SDA_Pin);
+
+ /* USER CODE BEGIN I2C2_MspDeInit 1 */
+
+ /* USER CODE END I2C2_MspDeInit 1 */
+ }
+
+}
+
+/**
+* @brief QSPI MSP Initialization
+* This function configures the hardware resources used in this example
+* @param hqspi: QSPI handle pointer
+* @retval None
+*/
+void HAL_QSPI_MspInit(QSPI_HandleTypeDef* hqspi)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(hqspi->Instance==QUADSPI)
+ {
+ /* USER CODE BEGIN QUADSPI_MspInit 0 */
+
+ /* USER CODE END QUADSPI_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_QSPI_CLK_ENABLE();
+
+ __HAL_RCC_GPIOE_CLK_ENABLE();
+ /**QUADSPI GPIO Configuration
+ PE10 ------> QUADSPI_CLK
+ PE11 ------> QUADSPI_NCS
+ PE12 ------> QUADSPI_BK1_IO0
+ PE13 ------> QUADSPI_BK1_IO1
+ PE14 ------> QUADSPI_BK1_IO2
+ PE15 ------> QUADSPI_BK1_IO3
+ */
+ GPIO_InitStruct.Pin = QUADSPI_CLK_Pin|QUADSPI_NCS_Pin|OQUADSPI_BK1_IO0_Pin|QUADSPI_BK1_IO1_Pin
+ |QUAD_SPI_BK1_IO2_Pin|QUAD_SPI_BK1_IO3_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF10_QUADSPI;
+ HAL_GPIO_Init(GPIOE, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN QUADSPI_MspInit 1 */
+
+ /* USER CODE END QUADSPI_MspInit 1 */
+ }
+
+}
+
+/**
+* @brief QSPI MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param hqspi: QSPI handle pointer
+* @retval None
+*/
+void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef* hqspi)
+{
+ if(hqspi->Instance==QUADSPI)
+ {
+ /* USER CODE BEGIN QUADSPI_MspDeInit 0 */
+
+ /* USER CODE END QUADSPI_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_QSPI_CLK_DISABLE();
+
+ /**QUADSPI GPIO Configuration
+ PE10 ------> QUADSPI_CLK
+ PE11 ------> QUADSPI_NCS
+ PE12 ------> QUADSPI_BK1_IO0
+ PE13 ------> QUADSPI_BK1_IO1
+ PE14 ------> QUADSPI_BK1_IO2
+ PE15 ------> QUADSPI_BK1_IO3
+ */
+ HAL_GPIO_DeInit(GPIOE, QUADSPI_CLK_Pin|QUADSPI_NCS_Pin|OQUADSPI_BK1_IO0_Pin|QUADSPI_BK1_IO1_Pin
+ |QUAD_SPI_BK1_IO2_Pin|QUAD_SPI_BK1_IO3_Pin);
+
+ /* USER CODE BEGIN QUADSPI_MspDeInit 1 */
+
+ /* USER CODE END QUADSPI_MspDeInit 1 */
+ }
+
+}
+
+/**
+* @brief SPI MSP Initialization
+* This function configures the hardware resources used in this example
+* @param hspi: SPI handle pointer
+* @retval None
+*/
+void HAL_SPI_MspInit(SPI_HandleTypeDef* hspi)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(hspi->Instance==SPI3)
+ {
+ /* USER CODE BEGIN SPI3_MspInit 0 */
+
+ /* USER CODE END SPI3_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_SPI3_CLK_ENABLE();
+
+ __HAL_RCC_GPIOC_CLK_ENABLE();
+ /**SPI3 GPIO Configuration
+ PC10 ------> SPI3_SCK
+ PC11 ------> SPI3_MISO
+ PC12 ------> SPI3_MOSI
+ */
+ GPIO_InitStruct.Pin = INTERNAL_SPI3_SCK_Pin|INTERNAL_SPI3_MISO_Pin|INTERNAL_SPI3_MOSI_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF6_SPI3;
+ HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN SPI3_MspInit 1 */
+
+ /* USER CODE END SPI3_MspInit 1 */
+ }
+
+}
+
+/**
+* @brief SPI MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param hspi: SPI handle pointer
+* @retval None
+*/
+void HAL_SPI_MspDeInit(SPI_HandleTypeDef* hspi)
+{
+ if(hspi->Instance==SPI3)
+ {
+ /* USER CODE BEGIN SPI3_MspDeInit 0 */
+
+ /* USER CODE END SPI3_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_SPI3_CLK_DISABLE();
+
+ /**SPI3 GPIO Configuration
+ PC10 ------> SPI3_SCK
+ PC11 ------> SPI3_MISO
+ PC12 ------> SPI3_MOSI
+ */
+ HAL_GPIO_DeInit(GPIOC, INTERNAL_SPI3_SCK_Pin|INTERNAL_SPI3_MISO_Pin|INTERNAL_SPI3_MOSI_Pin);
+
+ /* USER CODE BEGIN SPI3_MspDeInit 1 */
+
+ /* USER CODE END SPI3_MspDeInit 1 */
+ }
+
+}
+
+/**
+* @brief UART MSP Initialization
+* This function configures the hardware resources used in this example
+* @param huart: UART handle pointer
+* @retval None
+*/
+void HAL_UART_MspInit(UART_HandleTypeDef* huart)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(huart->Instance==USART1)
+ {
+ /* USER CODE BEGIN USART1_MspInit 0 */
+
+ /* USER CODE END USART1_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_USART1_CLK_ENABLE();
+
+ __HAL_RCC_GPIOB_CLK_ENABLE();
+ /**USART1 GPIO Configuration
+ PB6 ------> USART1_TX
+ PB7 ------> USART1_RX
+ */
+ GPIO_InitStruct.Pin = ST_LINK_UART1_TX_Pin|ST_LINK_UART1_RX_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF7_USART1;
+ HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN USART1_MspInit 1 */
+
+ /* USER CODE END USART1_MspInit 1 */
+ }
+ else if(huart->Instance==USART3)
+ {
+ /* USER CODE BEGIN USART3_MspInit 0 */
+
+ /* USER CODE END USART3_MspInit 0 */
+ /* Peripheral clock enable */
+ __HAL_RCC_USART3_CLK_ENABLE();
+
+ __HAL_RCC_GPIOD_CLK_ENABLE();
+ /**USART3 GPIO Configuration
+ PD8 ------> USART3_TX
+ PD9 ------> USART3_RX
+ */
+ GPIO_InitStruct.Pin = INTERNAL_UART3_TX_Pin|INTERNAL_UART3_RX_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF7_USART3;
+ HAL_GPIO_Init(GPIOD, &GPIO_InitStruct);
+
+ /* USER CODE BEGIN USART3_MspInit 1 */
+
+ /* USER CODE END USART3_MspInit 1 */
+ }
+
+}
+
+/**
+* @brief UART MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param huart: UART handle pointer
+* @retval None
+*/
+void HAL_UART_MspDeInit(UART_HandleTypeDef* huart)
+{
+ if(huart->Instance==USART1)
+ {
+ /* USER CODE BEGIN USART1_MspDeInit 0 */
+
+ /* USER CODE END USART1_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USART1_CLK_DISABLE();
+
+ /**USART1 GPIO Configuration
+ PB6 ------> USART1_TX
+ PB7 ------> USART1_RX
+ */
+ HAL_GPIO_DeInit(GPIOB, ST_LINK_UART1_TX_Pin|ST_LINK_UART1_RX_Pin);
+
+ /* USER CODE BEGIN USART1_MspDeInit 1 */
+
+ /* USER CODE END USART1_MspDeInit 1 */
+ }
+ else if(huart->Instance==USART3)
+ {
+ /* USER CODE BEGIN USART3_MspDeInit 0 */
+
+ /* USER CODE END USART3_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USART3_CLK_DISABLE();
+
+ /**USART3 GPIO Configuration
+ PD8 ------> USART3_TX
+ PD9 ------> USART3_RX
+ */
+ HAL_GPIO_DeInit(GPIOD, INTERNAL_UART3_TX_Pin|INTERNAL_UART3_RX_Pin);
+
+ /* USER CODE BEGIN USART3_MspDeInit 1 */
+
+ /* USER CODE END USART3_MspDeInit 1 */
+ }
+
+}
+
+/**
+* @brief PCD MSP Initialization
+* This function configures the hardware resources used in this example
+* @param hpcd: PCD handle pointer
+* @retval None
+*/
+void HAL_PCD_MspInit(PCD_HandleTypeDef* hpcd)
+{
+ GPIO_InitTypeDef GPIO_InitStruct = {0};
+ if(hpcd->Instance==USB_OTG_FS)
+ {
+ /* USER CODE BEGIN USB_OTG_FS_MspInit 0 */
+
+ /* USER CODE END USB_OTG_FS_MspInit 0 */
+
+ __HAL_RCC_GPIOA_CLK_ENABLE();
+ /**USB_OTG_FS GPIO Configuration
+ PA9 ------> USB_OTG_FS_VBUS
+ PA10 ------> USB_OTG_FS_ID
+ PA11 ------> USB_OTG_FS_DM
+ PA12 ------> USB_OTG_FS_DP
+ */
+ GPIO_InitStruct.Pin = USB_OTG_FS_VBUS_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ HAL_GPIO_Init(USB_OTG_FS_VBUS_GPIO_Port, &GPIO_InitStruct);
+
+ GPIO_InitStruct.Pin = USB_OTG_FS_ID_Pin|USB_OTG_FS_DM_Pin|USB_OTG_FS_DP_Pin;
+ GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
+ GPIO_InitStruct.Pull = GPIO_NOPULL;
+ GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
+ GPIO_InitStruct.Alternate = GPIO_AF10_OTG_FS;
+ HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
+
+ /* Peripheral clock enable */
+ __HAL_RCC_USB_OTG_FS_CLK_ENABLE();
+
+ /* Enable VDDUSB */
+ if(__HAL_RCC_PWR_IS_CLK_DISABLED())
+ {
+ __HAL_RCC_PWR_CLK_ENABLE();
+ HAL_PWREx_EnableVddUSB();
+ __HAL_RCC_PWR_CLK_DISABLE();
+ }
+ else
+ {
+ HAL_PWREx_EnableVddUSB();
+ }
+ /* USER CODE BEGIN USB_OTG_FS_MspInit 1 */
+
+ /* USER CODE END USB_OTG_FS_MspInit 1 */
+ }
+
+}
+
+/**
+* @brief PCD MSP De-Initialization
+* This function freeze the hardware resources used in this example
+* @param hpcd: PCD handle pointer
+* @retval None
+*/
+void HAL_PCD_MspDeInit(PCD_HandleTypeDef* hpcd)
+{
+ if(hpcd->Instance==USB_OTG_FS)
+ {
+ /* USER CODE BEGIN USB_OTG_FS_MspDeInit 0 */
+
+ /* USER CODE END USB_OTG_FS_MspDeInit 0 */
+ /* Peripheral clock disable */
+ __HAL_RCC_USB_OTG_FS_CLK_DISABLE();
+
+ /**USB_OTG_FS GPIO Configuration
+ PA9 ------> USB_OTG_FS_VBUS
+ PA10 ------> USB_OTG_FS_ID
+ PA11 ------> USB_OTG_FS_DM
+ PA12 ------> USB_OTG_FS_DP
+ */
+ HAL_GPIO_DeInit(GPIOA, USB_OTG_FS_VBUS_Pin|USB_OTG_FS_ID_Pin|USB_OTG_FS_DM_Pin|USB_OTG_FS_DP_Pin);
+
+ /* Disable VDDUSB */
+ if(__HAL_RCC_PWR_IS_CLK_DISABLED())
+ {
+ __HAL_RCC_PWR_CLK_ENABLE();
+ HAL_PWREx_DisableVddUSB();
+ __HAL_RCC_PWR_CLK_DISABLE();
+ }
+ else
+ {
+ HAL_PWREx_DisableVddUSB();
+ }
+ /* USER CODE BEGIN USB_OTG_FS_MspDeInit 1 */
+
+ /* USER CODE END USB_OTG_FS_MspDeInit 1 */
+ }
+
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_timebase_tim.c b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_timebase_tim.c
new file mode 100644
index 000000000..47f531b47
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_hal_timebase_tim.c
@@ -0,0 +1,114 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32l4xx_hal_timebase_TIM.c
+ * @brief HAL time base based on the hardware TIM.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; Copyright (c) 2019 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
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32l4xx_hal.h"
+#include "stm32l4xx_hal_tim.h"
+
+/* Private typedef -----------------------------------------------------------*/
+/* Private define ------------------------------------------------------------*/
+/* Private macro -------------------------------------------------------------*/
+/* Private variables ---------------------------------------------------------*/
+TIM_HandleTypeDef htim6;
+/* Private function prototypes -----------------------------------------------*/
+/* Private functions ---------------------------------------------------------*/
+
+/**
+ * @brief This function configures the TIM6 as a time base source.
+ * The time source is configured to have 1ms time base with a dedicated
+ * Tick interrupt priority.
+ * @note This function is called automatically at the beginning of program after
+ * reset by HAL_Init() or at any time when clock is configured, by HAL_RCC_ClockConfig().
+ * @param TickPriority: Tick interrupt priority.
+ * @retval HAL status
+ */
+HAL_StatusTypeDef HAL_InitTick(uint32_t TickPriority)
+{
+ RCC_ClkInitTypeDef clkconfig;
+ uint32_t uwTimclock = 0;
+ uint32_t uwPrescalerValue = 0;
+ uint32_t pFLatency;
+
+ /*Configure the TIM6 IRQ priority */
+ HAL_NVIC_SetPriority(TIM6_DAC_IRQn, TickPriority ,0);
+
+ /* Enable the TIM6 global Interrupt */
+ HAL_NVIC_EnableIRQ(TIM6_DAC_IRQn);
+
+ /* Enable TIM6 clock */
+ __HAL_RCC_TIM6_CLK_ENABLE();
+
+ /* Get clock configuration */
+ HAL_RCC_GetClockConfig(&clkconfig, &pFLatency);
+
+ /* Compute TIM6 clock */
+ uwTimclock = HAL_RCC_GetPCLK1Freq();
+
+ /* Compute the prescaler value to have TIM6 counter clock equal to 1MHz */
+ uwPrescalerValue = (uint32_t) ((uwTimclock / 1000000) - 1);
+
+ /* Initialize TIM6 */
+ htim6.Instance = TIM6;
+
+ /* Initialize TIMx peripheral as follow:
+ + Period = [(TIM6CLK/1000) - 1]. to have a (1/1000) s time base.
+ + Prescaler = (uwTimclock/1000000 - 1) to have a 1MHz counter clock.
+ + ClockDivision = 0
+ + Counter direction = Up
+ */
+ htim6.Init.Period = (1000000 / 1000) - 1;
+ htim6.Init.Prescaler = uwPrescalerValue;
+ htim6.Init.ClockDivision = 0;
+ htim6.Init.CounterMode = TIM_COUNTERMODE_UP;
+ if(HAL_TIM_Base_Init(&htim6) == HAL_OK)
+ {
+ /* Start the TIM time Base generation in interrupt mode */
+ return HAL_TIM_Base_Start_IT(&htim6);
+ }
+
+ /* Return function status */
+ return HAL_ERROR;
+}
+
+/**
+ * @brief Suspend Tick increment.
+ * @note Disable the tick increment by disabling TIM6 update interrupt.
+ * @param None
+ * @retval None
+ */
+void HAL_SuspendTick(void)
+{
+ /* Disable TIM6 update Interrupt */
+ __HAL_TIM_DISABLE_IT(&htim6, TIM_IT_UPDATE);
+}
+
+/**
+ * @brief Resume Tick increment.
+ * @note Enable the tick increment by Enabling TIM6 update interrupt.
+ * @param None
+ * @retval None
+ */
+void HAL_ResumeTick(void)
+{
+ /* Enable TIM6 Update interrupt */
+ __HAL_TIM_ENABLE_IT(&htim6, TIM_IT_UPDATE);
+}
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_it.c b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_it.c
new file mode 100644
index 000000000..f70742079
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/stm32l4xx_it.c
@@ -0,0 +1,200 @@
+/* USER CODE BEGIN Header */
+/**
+ ******************************************************************************
+ * @file stm32l4xx_it.c
+ * @brief Interrupt Service Routines.
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; Copyright (c) 2019 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
+ *
+ ******************************************************************************
+ */
+/* USER CODE END Header */
+
+/* Includes ------------------------------------------------------------------*/
+#include "main.h"
+#include "stm32l4xx_it.h"
+/* Private includes ----------------------------------------------------------*/
+/* USER CODE BEGIN Includes */
+/* USER CODE END Includes */
+
+/* Private typedef -----------------------------------------------------------*/
+/* USER CODE BEGIN TD */
+
+/* USER CODE END TD */
+
+/* Private define ------------------------------------------------------------*/
+/* USER CODE BEGIN PD */
+
+/* USER CODE END PD */
+
+/* Private macro -------------------------------------------------------------*/
+/* USER CODE BEGIN PM */
+
+/* USER CODE END PM */
+
+/* Private variables ---------------------------------------------------------*/
+/* USER CODE BEGIN PV */
+
+/* USER CODE END PV */
+
+/* Private function prototypes -----------------------------------------------*/
+/* USER CODE BEGIN PFP */
+
+/* USER CODE END PFP */
+
+/* Private user code ---------------------------------------------------------*/
+/* USER CODE BEGIN 0 */
+
+/* USER CODE END 0 */
+
+/* External variables --------------------------------------------------------*/
+extern TIM_HandleTypeDef htim6;
+
+/* USER CODE BEGIN EV */
+
+/* USER CODE END EV */
+
+/******************************************************************************/
+/* Cortex-M4 Processor Interruption and Exception Handlers */
+/******************************************************************************/
+/**
+ * @brief This function handles Non maskable interrupt.
+ */
+void NMI_Handler(void)
+{
+ /* USER CODE BEGIN NonMaskableInt_IRQn 0 */
+
+ /* USER CODE END NonMaskableInt_IRQn 0 */
+ /* USER CODE BEGIN NonMaskableInt_IRQn 1 */
+
+ /* USER CODE END NonMaskableInt_IRQn 1 */
+}
+
+/**
+ * @brief This function handles Hard fault interrupt.
+ */
+void HardFault_Handler(void)
+{
+ /* USER CODE BEGIN HardFault_IRQn 0 */
+
+ /* USER CODE END HardFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_HardFault_IRQn 0 */
+ /* USER CODE END W1_HardFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Prefetch fault, memory access fault.
+ */
+void BusFault_Handler(void)
+{
+ /* USER CODE BEGIN BusFault_IRQn 0 */
+
+ /* USER CODE END BusFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_BusFault_IRQn 0 */
+ /* USER CODE END W1_BusFault_IRQn 0 */
+ }
+}
+
+/**
+ * @brief This function handles Undefined instruction or illegal state.
+ */
+void UsageFault_Handler(void)
+{
+ /* USER CODE BEGIN UsageFault_IRQn 0 */
+
+ /* USER CODE END UsageFault_IRQn 0 */
+ while (1)
+ {
+ /* USER CODE BEGIN W1_UsageFault_IRQn 0 */
+ /* USER CODE END W1_UsageFault_IRQn 0 */
+ }
+}
+
+
+/**
+ * @brief This function handles Debug monitor.
+ */
+void DebugMon_Handler(void)
+{
+ /* USER CODE BEGIN DebugMonitor_IRQn 0 */
+
+ /* USER CODE END DebugMonitor_IRQn 0 */
+ /* USER CODE BEGIN DebugMonitor_IRQn 1 */
+
+ /* USER CODE END DebugMonitor_IRQn 1 */
+}
+
+
+/******************************************************************************/
+/* STM32L4xx Peripheral Interrupt Handlers */
+/* Add here the Interrupt Handlers for the used peripherals. */
+/* For the available peripheral interrupt handler names, */
+/* please refer to the startup file (startup_stm32l4xx.s). */
+/******************************************************************************/
+
+/**
+ * @brief This function handles EXTI line[9:5] interrupts.
+ */
+void EXTI9_5_IRQHandler(void)
+{
+ /* USER CODE BEGIN EXTI9_5_IRQn 0 */
+
+ /* USER CODE END EXTI9_5_IRQn 0 */
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_5);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_6);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_7);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_8);
+ /* USER CODE BEGIN EXTI9_5_IRQn 1 */
+
+ /* USER CODE END EXTI9_5_IRQn 1 */
+}
+
+/**
+ * @brief This function handles EXTI line[15:10] interrupts.
+ */
+void EXTI15_10_IRQHandler(void)
+{
+ /* USER CODE BEGIN EXTI15_10_IRQn 0 */
+
+ /* USER CODE END EXTI15_10_IRQn 0 */
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_10);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_11);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_13);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_14);
+ HAL_GPIO_EXTI_IRQHandler(GPIO_PIN_15);
+ /* USER CODE BEGIN EXTI15_10_IRQn 1 */
+
+ /* USER CODE END EXTI15_10_IRQn 1 */
+}
+
+/**
+ * @brief This function handles TIM6 global interrupt, DAC channel1 and channel2 underrun error interrupts.
+ */
+void TIM6_DAC_IRQHandler(void)
+{
+ /* USER CODE BEGIN TIM6_DAC_IRQn 0 */
+
+ /* USER CODE END TIM6_DAC_IRQn 0 */
+ HAL_TIM_IRQHandler(&htim6);
+ /* USER CODE BEGIN TIM6_DAC_IRQn 1 */
+
+ /* USER CODE END TIM6_DAC_IRQn 1 */
+}
+
+/* USER CODE BEGIN 1 */
+
+/* USER CODE END 1 */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/system_stm32l4xx.c b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/system_stm32l4xx.c
new file mode 100644
index 000000000..1db59ec93
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_MPU_STM32L4_Discovery_GCC_IAR_Keil/ST_Code/Core/Src/system_stm32l4xx.c
@@ -0,0 +1,337 @@
+/**
+ ******************************************************************************
+ * @file system_stm32l4xx.c
+ * @author MCD Application Team
+ * @brief CMSIS Cortex-M4 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_stm32l4xx.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.
+ *
+ * After each device reset the MSI (4 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32l4xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * This file configures the system clock as follows:
+ *=============================================================================
+ *-----------------------------------------------------------------------------
+ * System Clock source | MSI
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 4000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 4000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * PLL_M | 1
+ *-----------------------------------------------------------------------------
+ * PLL_N | 8
+ *-----------------------------------------------------------------------------
+ * PLL_P | 7
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 2
+ *-----------------------------------------------------------------------------
+ * PLL_R | 2
+ *-----------------------------------------------------------------------------
+ * PLLSAI1_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLSAI1_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLSAI1_R | NA
+ *-----------------------------------------------------------------------------
+ * PLLSAI2_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLSAI2_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLSAI2_R | NA
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>&copy; Copyright (c) 2017 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 stm32l4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32L4xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32l4xx.h"
+
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */
+#endif /* HSE_VALUE */
+
+#if !defined (MSI_VALUE)
+ #define MSI_VALUE 4000000U /*!< Value of the Internal oscillator in Hz*/
+#endif /* MSI_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/
+#endif /* HSI_VALUE */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L4xx_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 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L4xx_System_Private_Variables
+ * @{
+ */
+ /* The SystemCoreClock 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 = 4000000U;
+
+ 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 uint32_t MSIRangeTable[12] = {100000U, 200000U, 400000U, 800000U, 1000000U, 2000000U, \
+ 4000000U, 8000000U, 16000000U, 24000000U, 32000000U, 48000000U};
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32L4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system.
+ * @param None
+ * @retval None
+ */
+
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set MSION bit */
+ RCC->CR |= RCC_CR_MSION;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000U;
+
+ /* Reset HSEON, CSSON , HSION, and PLLON bits */
+ RCC->CR &= 0xEAF6FFFFU;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x00001000U;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= 0xFFFBFFFFU;
+
+ /* Disable all interrupts */
+ RCC->CIER = 0x00000000U;
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable 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(*)
+ *
+ * - 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(*) or MSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) MSI_VALUE is a constant defined in stm32l4xx_hal.h file (default value
+ * 4 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSI_VALUE is a constant defined in stm32l4xx_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 stm32l4xx_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, msirange = 0U, pllvco = 0U, pllr = 2U, pllsource = 0U, pllm = 2U;
+
+ /* Get MSI Range frequency--------------------------------------------------*/
+ if((RCC->CR & RCC_CR_MSIRGSEL) == RESET)
+ { /* MSISRANGE from RCC_CSR applies */
+ msirange = (RCC->CSR & RCC_CSR_MSISRANGE) >> 8U;
+ }
+ else
+ { /* MSIRANGE from RCC_CR applies */
+ msirange = (RCC->CR & RCC_CR_MSIRANGE) >> 4U;
+ }
+ /*MSI frequency range in HZ*/
+ msirange = MSIRangeTable[msirange];
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ switch (RCC->CFGR & RCC_CFGR_SWS)
+ {
+ case 0x00: /* MSI used as system clock source */
+ SystemCoreClock = msirange;
+ break;
+
+ case 0x04: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+
+ case 0x08: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+
+ case 0x0C: /* PLL used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE or MSI_VALUE/ PLLM) * PLLN
+ SYSCLK = PLL_VCO / PLLR
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC);
+ pllm = ((RCC->PLLCFGR & RCC_PLLCFGR_PLLM) >> 4U) + 1U ;
+
+ switch (pllsource)
+ {
+ case 0x02: /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm);
+ break;
+
+ case 0x03: /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm);
+ break;
+
+ default: /* MSI used as PLL clock source */
+ pllvco = (msirange / pllm);
+ break;
+ }
+ pllvco = pllvco * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 8U);
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >> 25U) + 1U) * 2U;
+ SystemCoreClock = pllvco/pllr;
+ break;
+
+ default:
+ SystemCoreClock = msirange;
+ break;
+ }
+ /* Compute HCLK clock frequency --------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4U)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/