diff --git a/boards.txt b/boards.txt
index 8617e7d8f9..5ba845f919 100644
--- a/boards.txt
+++ b/boards.txt
@@ -418,6 +418,10 @@ GenF103.menu.upload_method.serialMethod=Serial
GenF103.menu.upload_method.serialMethod.upload.protocol=maple_serial
GenF103.menu.upload_method.serialMethod.upload.tool=serial_upload
+GenF103.menu.upload_method.bmpMethod=BMP (Black Magic Probe)
+GenF103.menu.upload_method.bmpMethod.upload.protocol=gdb_bmp
+GenF103.menu.upload_method.bmpMethod.upload.tool=bmp_upload
+
###############################
# Maple
Maple.name=Maple series
diff --git a/cores/arduino/HardwareSerial.cpp b/cores/arduino/HardwareSerial.cpp
index 9f24275905..6177980390 100644
--- a/cores/arduino/HardwareSerial.cpp
+++ b/cores/arduino/HardwareSerial.cpp
@@ -182,6 +182,16 @@ void HardwareSerial::init(void)
_serial.tx_tail = 0;
}
+void HardwareSerial::configForLowPower(void)
+{
+#if defined(HAL_PWR_MODULE_ENABLED) && defined(UART_IT_WUF)
+ // Reconfigure properly Serial instance to use HSI as clock source
+ end();
+ uart_config_lowpower(&_serial);
+ begin(_serial.baudrate, _config);
+#endif
+}
+
// Actual interrupt handlers //////////////////////////////////////////////////////////////
void HardwareSerial::_rx_complete_irq(serial_t* obj)
@@ -226,6 +236,7 @@ void HardwareSerial::begin(unsigned long baud, byte config)
uint32_t databits = 0;
_serial.baudrate = (uint32_t)baud;
+ _config = config;
// Manage databits
switch(config & 0x07) {
diff --git a/cores/arduino/HardwareSerial.h b/cores/arduino/HardwareSerial.h
index 81a48add5f..dff7163745 100644
--- a/cores/arduino/HardwareSerial.h
+++ b/cores/arduino/HardwareSerial.h
@@ -125,11 +125,15 @@ class HardwareSerial : public Stream
void setRx(PinName _rx);
void setTx(PinName _tx);
+ friend class STM32LowPower;
+
// Interrupt handlers
static void _rx_complete_irq(serial_t* obj);
static int _tx_complete_irq(serial_t* obj);
private:
+ uint8_t _config;
void init(void);
+ void configForLowPower(void);
};
extern HardwareSerial Serial1;
diff --git a/cores/arduino/board.h b/cores/arduino/board.h
index 3ca81179e2..00e207e62a 100644
--- a/cores/arduino/board.h
+++ b/cores/arduino/board.h
@@ -14,6 +14,7 @@ extern "C"{
#include "digital_io.h"
#include "hal_uart_emul.h"
#include "hw_config.h"
+#include "low_power.h"
#include "rtc.h"
#include "spi_com.h"
#include "stm32_eeprom.h"
diff --git a/cores/arduino/main.cpp b/cores/arduino/main.cpp
index 3bf32a6616..741f041d0a 100644
--- a/cores/arduino/main.cpp
+++ b/cores/arduino/main.cpp
@@ -33,6 +33,15 @@ void initVariant() { }
// Required by FreeRTOS, see http://www.freertos.org/RTOS-Cortex-M3-M4.html
#ifdef NVIC_PRIORITYGROUP_4
HAL_NVIC_SetPriorityGrouping(NVIC_PRIORITYGROUP_4);
+#endif
+#if (__CORTEX_M == 0x07U)
+// Defined in CMSIS core_cm7.h
+#ifndef I_CACHE_DISABLED
+ SCB_EnableICache();
+#endif
+#ifndef D_CACHE_DISABLED
+ SCB_EnableDCache();
+#endif
#endif
init();
diff --git a/cores/arduino/stm32/PinNames.h b/cores/arduino/stm32/PinNames.h
index e1ed2e7dd4..d860db33a5 100644
--- a/cores/arduino/stm32/PinNames.h
+++ b/cores/arduino/stm32/PinNames.h
@@ -9,7 +9,10 @@ extern "C" {
#endif
typedef enum {
+ // Not connected
+ NC = (int)0xFFFFFFFF,
+ // Pin name definition
PA_0 = (PortA << 4) + 0x00,
PA_1 = (PortA << 4) + 0x01,
PA_2 = (PortA << 4) + 0x02,
@@ -205,8 +208,11 @@ typedef enum {
PK_14 = (PortK << 4) + 0x0E,
PK_15 = (PortK << 4) + 0x0F,
#endif
- // Not connected
- NC = (int)0xFFFFFFFF
+// Specific pin name define in the variant
+#if __has_include("PinNamesVar.h")
+#include "PinNamesVar.h"
+#endif
+ P_END = NC
} PinName;
#ifdef __cplusplus
diff --git a/cores/arduino/stm32/low_power.c b/cores/arduino/stm32/low_power.c
new file mode 100644
index 0000000000..7f09544ab9
--- /dev/null
+++ b/cores/arduino/stm32/low_power.c
@@ -0,0 +1,328 @@
+/**
+ ******************************************************************************
+ * @file LowPower.c
+ * @author WI6LABS
+ * @version V1.0.0
+ * @date 17 - November -2017
+ * @brief Provides a Low Power interface
+ *
+ ******************************************************************************
+ * @attention
+ *
+ *
© COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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 "Arduino.h"
+#include "low_power.h"
+
+#ifdef HAL_PWR_MODULE_ENABLED
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+#ifdef UART_IT_WUF
+/* Save UART handler for callback */
+static UART_HandleTypeDef* WakeUpUart = NULL;
+#endif
+/* Save callback pointer */
+static void (*WakeUpUartCb)( void ) = NULL;
+
+/**
+ * @brief Initialize low power mode
+ * @param None
+ * @retval None
+ */
+void LowPower_init(){
+ /* Enable Power Clock */
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+ /* Allow access to Backup domain */
+ HAL_PWR_EnableBkUpAccess();
+
+#ifdef __HAL_RCC_WAKEUPSTOP_CLK_CONFIG
+ /* Ensure that HSI is wake-up system clock */
+ __HAL_RCC_WAKEUPSTOP_CLK_CONFIG(RCC_STOP_WAKEUPCLOCK_HSI);
+#endif
+ /* Check if the system was resumed from StandBy mode */
+ if (__HAL_PWR_GET_FLAG(PWR_FLAG_SB) != RESET)
+ {
+ /* Clear Standby flag */
+ __HAL_PWR_CLEAR_FLAG(PWR_FLAG_SB);
+ }
+
+ /* Clear all related wakeup flags */
+ __HAL_PWR_CLEAR_FLAG(PWR_FLAG_WU);
+}
+
+/**
+ * @brief Configure a pin as wakeup source if compatible.
+ * @param pin: pin to configure
+ * @param mode: pin mode (edge or state). The configuration have to be compatible.
+ * @retval None
+ */
+void LowPower_EnableWakeUpPin(uint32_t pin, uint32_t mode) {
+#if !defined(PWR_WAKEUP_PIN1_HIGH)
+ UNUSED(mode);
+#endif
+ uint32_t wkup_pin;
+ PinName p = digitalPinToPinName(pin);
+ if (p != NC) {
+ switch (p) {
+ default :
+#ifdef PWR_WAKEUP_PIN1
+ case SYS_WKUP1 :
+ wkup_pin = PWR_WAKEUP_PIN1;
+#ifdef PWR_WAKEUP_PIN1_HIGH
+ if (mode != RISING) {
+ wkup_pin = PWR_WAKEUP_PIN1_LOW;
+ }
+#endif
+ break;
+#endif /* PWR_WAKEUP_PIN1 */
+#ifdef PWR_WAKEUP_PIN2
+ case SYS_WKUP2 :
+ wkup_pin = PWR_WAKEUP_PIN2;
+#ifdef PWR_WAKEUP_PIN2_HIGH
+ if (mode != RISING) {
+ wkup_pin = PWR_WAKEUP_PIN2_LOW;
+ }
+#endif
+ break;
+#endif /* PWR_WAKEUP_PIN2 */
+#ifdef PWR_WAKEUP_PIN3
+ case SYS_WKUP3 :
+ wkup_pin = PWR_WAKEUP_PIN3;
+#ifdef PWR_WAKEUP_PIN3_HIGH
+ if (mode != RISING) {
+ wkup_pin = PWR_WAKEUP_PIN3_LOW;
+ }
+#endif
+ break;
+#endif /* PWR_WAKEUP_PIN3 */
+#ifdef PWR_WAKEUP_PIN4
+ case SYS_WKUP4 :
+ wkup_pin = PWR_WAKEUP_PIN4;
+#ifdef PWR_WAKEUP_PIN4_HIGH
+ if (mode != RISING) {
+ wkup_pin = PWR_WAKEUP_PIN4_LOW;
+ }
+#endif
+ break;
+#endif /* PWR_WAKEUP_PIN4 */
+#ifdef PWR_WAKEUP_PIN5
+ case SYS_WKUP5 :
+ wkup_pin = PWR_WAKEUP_PIN5;
+#ifdef PWR_WAKEUP_PIN5_HIGH
+ if (mode != RISING) {
+ wkup_pin = PWR_WAKEUP_PIN5_LOW;
+ }
+#endif
+ break;
+#endif /* PWR_WAKEUP_PIN5 */
+#ifdef PWR_WAKEUP_PIN6
+ case SYS_WKUP6 :
+ wkup_pin = PWR_WAKEUP_PIN6;
+#ifdef PWR_WAKEUP_PIN6_HIGH
+ if (mode != RISING) {
+ wkup_pin = PWR_WAKEUP_PIN6_LOW;
+ }
+#endif
+ break;
+#endif /* PWR_WAKEUP_PIN6 */
+#ifdef PWR_WAKEUP_PIN7
+ case SYS_WKUP7 :
+ wkup_pin = PWR_WAKEUP_PIN7;
+ break;
+#endif /* PWR_WAKEUP_PIN7 */
+#ifdef PWR_WAKEUP_PIN8
+ case SYS_WKUP8 :
+ wkup_pin = PWR_WAKEUP_PIN8;
+ break;
+#endif /* PWR_WAKEUP_PIN8 */
+ }
+ HAL_PWR_EnableWakeUpPin(wkup_pin);
+ }
+}
+
+/**
+ * @brief Enable the sleep mode.
+ * @param None
+ * @retval None
+ */
+void LowPower_sleep(uint32_t regulator){
+ /*
+ * Suspend Tick increment to prevent wakeup by Systick interrupt.
+ * Otherwise the Systick interrupt will wake up the device within
+ * 1ms (HAL time base)
+ */
+ HAL_SuspendTick();
+
+ /* Enter Sleep Mode , wake up is done once User push-button is pressed */
+ HAL_PWR_EnterSLEEPMode(regulator, PWR_SLEEPENTRY_WFI);
+
+ /* Resume Tick interrupt if disabled prior to SLEEP mode entry */
+ HAL_ResumeTick();
+
+ if (WakeUpUartCb != NULL) {
+ WakeUpUartCb();
+ }
+}
+
+/**
+ * @brief Enable the stop mode.
+ * @param obj : pointer to serial_t structure
+ * @retval None
+ */
+void LowPower_stop(serial_t *obj){
+ __disable_irq();
+
+#ifdef UART_IT_WUF
+ if (WakeUpUart != NULL) {
+ HAL_UARTEx_EnableStopMode(WakeUpUart);
+ }
+#endif
+
+#if defined(STM32L0xx) || defined(STM32L1xx)
+ /* Enable Ultra low power mode */
+ HAL_PWREx_EnableUltraLowPower();
+
+ /* Enable the fast wake up from Ultra low power mode */
+ HAL_PWREx_EnableFastWakeUp();
+#endif
+#ifdef __HAL_RCC_WAKEUPSTOP_CLK_CONFIG
+ /* Select HSI as system clock source after Wake Up from Stop mode */
+ __HAL_RCC_WAKEUPSTOP_CLK_CONFIG(RCC_STOP_WAKEUPCLOCK_HSI);
+#endif
+
+ /* Enter Stop mode */
+ HAL_PWR_EnterSTOPMode(PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI);
+
+ /* Exit Stop mode reset clocks */
+ SystemClock_Config();
+#ifdef UART_IT_WUF
+ if (WakeUpUart != NULL) {
+ /* In case of WakeUp from UART, reset its clock source to HSI */
+ uart_config_lowpower(obj);
+ HAL_UARTEx_DisableStopMode(WakeUpUart);
+ }
+#else
+ UNUSED(obj);
+#endif
+ __enable_irq();
+
+ HAL_Delay(10);
+
+ if (WakeUpUartCb != NULL) {
+ WakeUpUartCb();
+ }
+}
+
+/**
+ * @brief Enable the standby mode. The board reset when leaves this mode.
+ * @param None
+ * @retval None
+ */
+void LowPower_standby(){
+ __disable_irq();
+
+#if defined(STM32L0xx) || defined(STM32L1xx)
+ /* Enable Ultra low power mode */
+ HAL_PWREx_EnableUltraLowPower();
+
+ /* Enable the fast wake up from Ultra low power mode */
+ HAL_PWREx_EnableFastWakeUp();
+#endif
+
+ HAL_PWR_EnterSTANDBYMode();
+}
+
+/**
+ * @brief Enable the shutdown mode.The board reset when leaves this mode.
+ * If shutdown mode not available, use standby mode instead.
+ * @param None
+ * @retval None
+ */
+void LowPower_shutdown(){
+ __disable_irq();
+#ifdef STM32L4xx
+ /* LSE must be on to use shutdown mode */
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_LSERDY) == SET) {
+ HAL_PWREx_EnterSHUTDOWNMode();
+ } else
+#endif
+ {
+ LowPower_standby();
+ }
+}
+
+/**
+ * @brief Configure the UART as a wakeup source. A callback can be called when
+ * the chip leaves the low power mode. See board datasheet to check
+ * with which low power mode the UART is compatible.
+ * Warning This function will change UART clock source to HSI
+ * @param serial: pointer to serial
+ * @param FuncPtr: pointer to callback
+ * @retval None
+ */
+void LowPower_EnableWakeUpUart(serial_t* serial, void (*FuncPtr)( void ) ) {
+#ifdef UART_IT_WUF
+ UART_WakeUpTypeDef WakeUpSelection;
+ if(serial == NULL) {
+ return;
+ }
+ /* Save Uart handler and Serial object */
+ WakeUpUart = &(serial->handle);
+
+ /* make sure that no UART transfer is on-going */
+ while(__HAL_UART_GET_FLAG(WakeUpUart, USART_ISR_BUSY) == SET);
+ /* make sure that UART is ready to receive
+ * (test carried out again later in HAL_UARTEx_StopModeWakeUpSourceConfig) */
+ while(__HAL_UART_GET_FLAG(WakeUpUart, USART_ISR_REACK) == RESET);
+
+ /* set the wake-up event:
+ * specify wake-up on RXNE flag
+ */
+ WakeUpSelection.WakeUpEvent = UART_WAKEUP_ON_READDATA_NONEMPTY;
+ HAL_UARTEx_StopModeWakeUpSourceConfig(WakeUpUart, WakeUpSelection);
+
+ /* Enable the UART Wake UP from STOP1 mode Interrupt */
+ __HAL_UART_ENABLE_IT(WakeUpUart, UART_IT_WUF);
+#else
+ UNUSED(serial);
+#endif
+ /* Save callback */
+ WakeUpUartCb = FuncPtr;
+}
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/cores/arduino/stm32/low_power.h b/cores/arduino/stm32/low_power.h
new file mode 100644
index 0000000000..81d5baf136
--- /dev/null
+++ b/cores/arduino/stm32/low_power.h
@@ -0,0 +1,71 @@
+/**
+ ******************************************************************************
+ * @file LowPower.h
+ * @author WI6LABS
+ * @version V1.0.0
+ * @date 17 - November -2017
+ * @brief Header for Low Power module
+ ******************************************************************************
+ * @attention
+ *
+ * © COPYRIGHT(c) 2017 STMicroelectronics
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+/* Define to prevent recursive inclusion -------------------------------------*/
+#ifndef __LOW_POWER_H
+#define __LOW_POWER_H
+
+/* Includes ------------------------------------------------------------------*/
+#include "stm32_def.h"
+#include "uart.h"
+
+#ifdef HAL_PWR_MODULE_ENABLED
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/* Exported types ------------------------------------------------------------*/
+/* Exported constants --------------------------------------------------------*/
+/* Exported macro ------------------------------------------------------------*/
+/* Exported functions ------------------------------------------------------- */
+
+void LowPower_init();
+void LowPower_EnableWakeUpPin(uint32_t pin, uint32_t mode);
+void LowPower_EnableWakeUpUart(serial_t* serial, void (*FuncPtr)( void ) );
+void LowPower_sleep(uint32_t regulator);
+void LowPower_stop(serial_t *obj);
+void LowPower_standby();
+void LowPower_shutdown();
+
+#ifdef __cplusplus
+ }
+#endif
+
+#endif /* HAL_PWR_MODULE_ENABLED */
+
+#endif /* __LOW_POWER_H */
diff --git a/cores/arduino/stm32/rtc.c b/cores/arduino/stm32/rtc.c
index a4350edf1d..1f9398d4ad 100644
--- a/cores/arduino/stm32/rtc.c
+++ b/cores/arduino/stm32/rtc.c
@@ -314,6 +314,17 @@ void RTC_init(hourFormat_t format, sourceClock_t source)
{
initFormat = format;
+ /* Enable Power Clock */
+ __HAL_RCC_PWR_CLK_ENABLE();
+
+#ifdef HAL_PWR_MODULE_ENABLED
+ /* Allow access to Backup domain */
+ HAL_PWR_EnableBkUpAccess();
+#endif
+ /* Reset RTC Domain */
+ __HAL_RCC_BACKUPRESET_FORCE();
+ __HAL_RCC_BACKUPRESET_RELEASE();
+
/* Init RTC clock */
RTC_initClock(source);
@@ -347,7 +358,7 @@ void RTC_init(hourFormat_t format, sourceClock_t source)
/*at 0:0:0*/
RTC_SetTime(0,0,0,0,AM);
-#if !defined(STM32F1xx) && !defined(STM32F2xx)
+#if !defined(STM32F1xx) && !defined(STM32F2xx) && !defined(STM32L1xx) || defined(STM32L1_ULPH)
/* Enable Direct Read of the calendar registers (not through Shadow) */
HAL_RTCEx_EnableBypassShadow(&RtcHandle);
#endif /* !STM32F1xx && !STM32F2xx */
@@ -443,7 +454,12 @@ void RTC_GetTime(uint8_t *hours, uint8_t *minutes, uint8_t *seconds, uint32_t *s
if(subSeconds != NULL) {
*subSeconds = RTC_TimeStruct.SubSeconds;
}
+#else
+ UNUSED(subSeconds);
#endif
+#else
+ UNUSED(period);
+ UNUSED(subSeconds);
#endif /* !STM32F1xx */
}
}
@@ -581,19 +597,21 @@ void RTC_StopAlarm(void)
/**
* @brief Get RTC alarm
- * @param day: 1-31 (day of the month)
- * @param hours: 0-12 or 0-23 depends on the hours mode.
+ * @param day: 1-31 day of the month (optional could be NULL)
+ * @param hours: 0-12 or 0-23 depends on the hours mode
* @param minutes: 0-59
* @param seconds: 0-59
* @param subSeconds: 0-999 (optional could be NULL)
* @param period: AM or PM (optional could be NULL)
+ * @param mask: alarm behavior using alarmMask_t combination (optional could be NULL)
+ * See AN4579 Table 5 for possible values
* @retval None
*/
void RTC_GetAlarm(uint8_t *day, uint8_t *hours, uint8_t *minutes, uint8_t *seconds, uint32_t *subSeconds, hourAM_PM_t *period, uint8_t *mask)
{
RTC_AlarmTypeDef RTC_AlarmStructure;
- if((day != NULL) && (hours != NULL) && (minutes != NULL) && (seconds != NULL) && (mask != NULL)) {
+ if((hours != NULL) && (minutes != NULL) && (seconds != NULL)) {
HAL_RTC_GetAlarm(&RtcHandle, &RTC_AlarmStructure, RTC_ALARM_A, RTC_FORMAT_BIN);
*seconds = RTC_AlarmStructure.AlarmTime.Seconds;
@@ -601,7 +619,9 @@ void RTC_GetAlarm(uint8_t *day, uint8_t *hours, uint8_t *minutes, uint8_t *secon
*hours = RTC_AlarmStructure.AlarmTime.Hours;
#if !defined(STM32F1xx)
- *day = RTC_AlarmStructure.AlarmDateWeekDay;
+ if (day != NULL) {
+ *day = RTC_AlarmStructure.AlarmDateWeekDay;
+ }
if(period != NULL) {
if(RTC_AlarmStructure.AlarmTime.TimeFormat == RTC_HOURFORMAT12_PM) {
*period = PM;
@@ -613,20 +633,29 @@ void RTC_GetAlarm(uint8_t *day, uint8_t *hours, uint8_t *minutes, uint8_t *secon
if(subSeconds != NULL) {
*subSeconds = RTC_AlarmStructure.AlarmTime.SubSeconds;
}
+#else
+ UNUSED(subSeconds);
#endif /* !STM32F2xx && !STM32L1xx || STM32L1_ULPH */
- *mask = OFF_MSK;
- if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_SECONDS)) {
- *mask |= SS_MSK;
- }
- if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_MINUTES)) {
- *mask |= MM_MSK;
- }
- if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_HOURS)) {
- *mask |= HH_MSK;
- }
- if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_DATEWEEKDAY)) {
- *mask |= D_MSK;
+ if (mask != NULL) {
+ *mask = OFF_MSK;
+ if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_SECONDS)) {
+ *mask |= SS_MSK;
+ }
+ if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_MINUTES)) {
+ *mask |= MM_MSK;
+ }
+ if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_HOURS)) {
+ *mask |= HH_MSK;
+ }
+ if(!(RTC_AlarmStructure.AlarmMask & RTC_ALARMMASK_DATEWEEKDAY)) {
+ *mask |= D_MSK;
+ }
}
+#else
+ UNUSED(day);
+ UNUSED(period);
+ UNUSED(subSeconds);
+ UNUSED(mask);
#endif /* !STM32F1xx */
}
}
diff --git a/cores/arduino/stm32/spi_com.c b/cores/arduino/stm32/spi_com.c
index a7d55da439..eaca8c5a47 100644
--- a/cores/arduino/stm32/spi_com.c
+++ b/cores/arduino/stm32/spi_com.c
@@ -118,7 +118,7 @@ uint32_t spi_getClkFreqInst(SPI_TypeDef * spi_inst)
if(spi_inst != NP) {
/* Get source clock depending on SPI instance */
switch ((uint32_t)spi_inst) {
-#if defined(SPI1_BASE) || defined(SPI4_BASE) || defined(SPI5_BASE) || defined(SPI16_BASE)
+#if defined(SPI1_BASE) || defined(SPI4_BASE) || defined(SPI5_BASE) || defined(SPI6_BASE)
/* Some STM32's (eg. STM32F302x8) have no SPI1, but do have SPI2/3. */
#if defined SPI1_BASE
case (uint32_t)SPI1:
diff --git a/cores/arduino/stm32/uart.c b/cores/arduino/stm32/uart.c
index af72dd5fa1..dc054c758b 100644
--- a/cores/arduino/stm32/uart.c
+++ b/cores/arduino/stm32/uart.c
@@ -125,6 +125,7 @@ void uart_init(serial_t *obj)
printf("ERROR: UART pins mismatch\n");
return;
}
+
// Enable USART clock
#if defined(USART1_BASE)
else if(obj->uart == USART1) {
@@ -288,6 +289,10 @@ void uart_init(serial_t *obj)
huart->Init.Mode = UART_MODE_TX_RX;
huart->Init.HwFlowCtl = UART_HWCONTROL_NONE;
huart->Init.OverSampling = UART_OVERSAMPLING_16;
+#if !defined(STM32F1xx) && !defined(STM32F2xx) && !defined(STM32F4xx)\
+ && !defined(STM32L1xx)
+ huart->AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_NO_INIT;
+#endif
// huart->Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
if(HAL_UART_Init(huart) != HAL_OK) {
@@ -403,6 +408,69 @@ void uart_deinit(serial_t *obj)
HAL_UART_DeInit(uart_handlers[obj->index]);
}
+#if defined(HAL_PWR_MODULE_ENABLED) && defined(UART_IT_WUF)
+/**
+ * @brief Function called to configure the uart interface for low power
+ * @param obj : pointer to serial_t structure
+ * @retval None
+ */
+void uart_config_lowpower(serial_t *obj)
+{
+ if(obj == NULL) {
+ return;
+ }
+ RCC_OscInitTypeDef RCC_OscInitStruct = {0};
+ /* Ensure HSI clock is enable */
+ if(__HAL_RCC_GET_FLAG(RCC_FLAG_HSIRDY) == RESET) {
+ RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
+ RCC_OscInitStruct.HSIState = RCC_HSI_ON;
+ RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
+ RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
+ if (HAL_RCC_OscConfig(&RCC_OscInitStruct)!= HAL_OK) {
+ Error_Handler();
+ }
+ }
+ /* Configure HSI as source clock for low power wakeup clock */
+ switch (obj->index) {
+#if defined(USART1_BASE)
+ case 0:
+ if (__HAL_RCC_GET_USART1_SOURCE() != RCC_USART1CLKSOURCE_HSI) {
+ __HAL_RCC_USART1_CONFIG(RCC_USART1CLKSOURCE_HSI);
+ }
+ break;
+#endif
+#if defined(USART2_BASE) && defined(__HAL_RCC_USART2_CONFIG)
+ case 1:
+ if (__HAL_RCC_GET_USART2_SOURCE() != RCC_USART2CLKSOURCE_HSI) {
+ __HAL_RCC_USART2_CONFIG(RCC_USART2CLKSOURCE_HSI);
+ }
+ break;
+#endif
+#if defined(USART3_BASE) && defined(__HAL_RCC_USART3_CONFIG)
+ case 2:
+ if (__HAL_RCC_GET_USART3_SOURCE() != RCC_USART3CLKSOURCE_HSI) {
+ __HAL_RCC_USART3_CONFIG(RCC_USART3CLKSOURCE_HSI);
+ }
+ break;
+#endif
+#if defined(UART4_BASE) && defined(__HAL_RCC_UART4_CONFIG)
+ case 3:
+ if (__HAL_RCC_GET_UART4_SOURCE() != RCC_UART4CLKSOURCE_HSI) {
+ __HAL_RCC_UART4_CONFIG(RCC_UART4CLKSOURCE_HSI);
+ }
+ break;
+#endif
+#if defined(UART5_BASE) && defined(__HAL_RCC_UART5_CONFIG)
+ case 4:
+ if (__HAL_RCC_GET_UART5_SOURCE() != RCC_UART5CLKSOURCE_HSI) {
+ __HAL_RCC_UART5_CONFIG(RCC_UART5CLKSOURCE_HSI);
+ }
+ break;
+#endif
+ }
+}
+#endif
+
/**
* @brief write the data on the uart
* @param obj : pointer to serial_t structure
@@ -866,6 +934,19 @@ void UART10_IRQHandler(void)
}
#endif
+/**
+ * @brief HAL UART Call Back
+ * @param UART handler
+ * @retval None
+ */
+void HAL_UARTEx_WakeupCallback(UART_HandleTypeDef *huart)
+{
+ uint8_t index = uart_index(huart);
+ serial_t *obj = rx_callback_obj[index];
+
+ HAL_UART_Receive_IT(huart, &(obj->recv), 1);
+}
+
#ifdef __cplusplus
}
#endif
diff --git a/cores/arduino/stm32/uart.h b/cores/arduino/stm32/uart.h
index 66cd5162a9..97707c80fe 100644
--- a/cores/arduino/stm32/uart.h
+++ b/cores/arduino/stm32/uart.h
@@ -279,6 +279,9 @@ struct serial_s {
/* Exported functions ------------------------------------------------------- */
void uart_init(serial_t *obj);
void uart_deinit(serial_t *obj);
+#if defined(HAL_PWR_MODULE_ENABLED) && defined(UART_IT_WUF)
+void uart_config_lowpower(serial_t *obj);
+#endif
size_t uart_write(serial_t *obj, uint8_t data, uint16_t size);
int uart_getc(serial_t *obj, unsigned char* c);
void uart_attach_rx_callback(serial_t *obj, void (*callback)(serial_t*));
diff --git a/cores/arduino/wiring_private.h b/cores/arduino/wiring_private.h
index a9608cef04..cf411613c6 100644
--- a/cores/arduino/wiring_private.h
+++ b/cores/arduino/wiring_private.h
@@ -1,5 +1,8 @@
/*
- Copyright (c) 2011 Arduino. All right reserved.
+ wiring_private.h - Internal header file.
+ Part of Arduino - http://www.arduino.cc/
+
+ Copyright (c) 2005-2006 David A. Mellis
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
@@ -8,15 +11,19 @@
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
- See the GNU Lesser General Public License for more details.
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
- You should have received a copy of the GNU Lesser General Public
- License along with this library; if not, write to the Free Software
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+ You should have received a copy of the GNU Lesser General
+ Public License along with this library; if not, write to the
+ Free Software Foundation, Inc., 59 Temple Place, Suite 330,
+ Boston, MA 02111-1307 USA
*/
#ifndef WiringPrivate_h
#define WiringPrivate_h
+#include
+#include
+
#endif
diff --git a/platform.txt b/platform.txt
index 8aec01d6d4..5425382cae 100644
--- a/platform.txt
+++ b/platform.txt
@@ -29,7 +29,7 @@ compiler.c.elf.cmd=arm-none-eabi-gcc
compiler.objcopy.cmd=arm-none-eabi-objcopy
compiler.elf2hex.cmd=arm-none-eabi-objcopy
-compiler.extra_flags=-mcpu={build.mcu} -mthumb @{build.opt.path}
+compiler.extra_flags=-mcpu={build.mcu} -mthumb "@{build.opt.path}"
compiler.S.flags={compiler.extra_flags} -c -x assembler-with-cpp {compiler.stm.extra_include}
@@ -172,3 +172,11 @@ tools.serial_upload.path.linux64={runtime.hardware.path}/tools/linux64
tools.serial_upload.upload.params.verbose=-d
tools.serial_upload.upload.params.quiet=n
tools.serial_upload.upload.pattern="{path}/{cmd}" {serial.port.file} {upload.altID} {upload.usbID} "{build.path}/{build.project_name}.bin"
+
+# blackmagic upload for generic STM32
+tools.bmp_upload.cmd=arm-none-eabi-gdb
+tools.bmp_upload.path={runtime.tools.arm-none-eabi-gcc.path}/bin/
+tools.bmp_upload.upload.speed=230400
+tools.bmp_upload.upload.params.verbose=-batch
+tools.bmp_upload.upload.params.quiet=--batch-silent
+tools.bmp_upload.upload.pattern="{path}{cmd}" -nx -b {upload.speed} {upload.verbose} -ex "set confirm off" -ex "target extended-remote {serial.port}" -ex "monitor swdp_scan" -ex "attach 1" -ex "load" -ex "compare-sections" -ex "kill" "{build.path}/{build.project_name}.elf"
diff --git a/variants/BLUEPILL_F103C8/PinNamesVar.h b/variants/BLUEPILL_F103C8/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/BLUEPILL_F103C8/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/BLUEPILL_F103C8/stm32f1xx_hal_conf.h b/variants/BLUEPILL_F103C8/stm32f1xx_hal_conf.h
index 9369936ed5..b466615b2f 100644
--- a/variants/BLUEPILL_F103C8/stm32f1xx_hal_conf.h
+++ b/variants/BLUEPILL_F103C8/stm32f1xx_hal_conf.h
@@ -70,7 +70,7 @@
/*#define HAL_NOR_MODULE_ENABLED*/
/*#define HAL_PCCARD_MODULE_ENABLED*/
/*#define HAL_PCD_MODULE_ENABLED*/
-/*#define HAL_PWR_MODULE_ENABLED*/
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
/*#define HAL_SD_MODULE_ENABLED*/
diff --git a/variants/DISCO_F100RB/PinNamesVar.h b/variants/DISCO_F100RB/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/DISCO_F100RB/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/DISCO_F100RB/stm32f1xx_hal_conf.h b/variants/DISCO_F100RB/stm32f1xx_hal_conf.h
index 78f5c5cf4d..36a5689a7f 100644
--- a/variants/DISCO_F100RB/stm32f1xx_hal_conf.h
+++ b/variants/DISCO_F100RB/stm32f1xx_hal_conf.h
@@ -70,7 +70,7 @@
/*#define HAL_NOR_MODULE_ENABLED*/
/*#define HAL_PCCARD_MODULE_ENABLED*/
/*#define HAL_PCD_MODULE_ENABLED*/
-/*#define HAL_PWR_MODULE_ENABLED*/
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
/*#define HAL_SD_MODULE_ENABLED*/
diff --git a/variants/DISCO_F407VG/PinNamesVar.h b/variants/DISCO_F407VG/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/DISCO_F407VG/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/DISCO_F746NG/PinNamesVar.h b/variants/DISCO_F746NG/PinNamesVar.h
new file mode 100644
index 0000000000..8ec2fab4aa
--- /dev/null
+++ b/variants/DISCO_F746NG/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PA_2,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = PC_1,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = PI_8,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = PI_11,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/DISCO_F746NG/variant.cpp b/variants/DISCO_F746NG/variant.cpp
index 027661de9f..5f98190d2a 100644
--- a/variants/DISCO_F746NG/variant.cpp
+++ b/variants/DISCO_F746NG/variant.cpp
@@ -63,7 +63,7 @@ extern "C" {
/**
* @brief System Clock Configuration
- * The system Clock is configured as follow :
+ * The system Clock is configured as follow :
* System Clock source = PLL (HSE)
* SYSCLK(Hz) = 216000000
* HCLK(Hz) = 216000000
@@ -89,16 +89,14 @@ WEAK void SystemClock_Config(void)
RCC_ClkInitTypeDef RCC_ClkInitStruct;
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
- /**Configure the main internal regulator output voltage
- */
+ /* Configure the main internal regulator output voltage */
__HAL_RCC_PWR_CLK_ENABLE();
__HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1);
- /**Initializes the CPU, AHB and APB busses clocks
- */
+ /* Initializes the CPU, AHB and APB busses clocks */
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
- RCC_OscInitStruct.HSEState = RCC_HSE_BYPASS;
+ RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = 25;
@@ -107,18 +105,16 @@ WEAK void SystemClock_Config(void)
RCC_OscInitStruct.PLL.PLLQ = 9;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
- while(1) { ; }
+ _Error_Handler(__FILE__, __LINE__);
}
- /**Activate the Over-Drive mode
- */
+ /* Activate the Over-Drive mode */
if (HAL_PWREx_EnableOverDrive() != HAL_OK)
{
- while(1) { ; }
+ _Error_Handler(__FILE__, __LINE__);
}
- /**Initializes the CPU, AHB and APB busses clocks
- */
+ /* 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;
@@ -128,26 +124,28 @@ WEAK void SystemClock_Config(void)
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_7) != HAL_OK)
{
- while(1) { ; }
+ _Error_Handler(__FILE__, __LINE__);
}
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LTDC|RCC_PERIPHCLK_USART1
|RCC_PERIPHCLK_CLK48;
PeriphClkInitStruct.PLLSAI.PLLSAIN = 192;
- PeriphClkInitStruct.PLLSAI.PLLSAIR = 2;
+ PeriphClkInitStruct.PLLSAI.PLLSAIR = 5;
PeriphClkInitStruct.PLLSAI.PLLSAIQ = 2;
PeriphClkInitStruct.PLLSAI.PLLSAIP = RCC_PLLSAIP_DIV4;
PeriphClkInitStruct.PLLSAIDivQ = 1;
- PeriphClkInitStruct.PLLSAIDivR = RCC_PLLSAIDIVR_2;
+ PeriphClkInitStruct.PLLSAIDivR = RCC_PLLSAIDIVR_4;
PeriphClkInitStruct.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
PeriphClkInitStruct.Clk48ClockSelection = RCC_CLK48SOURCE_PLLSAIP;
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct) != HAL_OK)
{
- while(1) { ; }
+ _Error_Handler(__FILE__, __LINE__);
}
+ /* Configure the Systick interrupt time */
HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq()/1000);
+ /* Configure the Systick */
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
/* SysTick_IRQn interrupt configuration */
diff --git a/variants/DISCO_L072CZ_LRWAN1/PinNamesVar.h b/variants/DISCO_L072CZ_LRWAN1/PinNamesVar.h
new file mode 100644
index 0000000000..0b7fa5cc33
--- /dev/null
+++ b/variants/DISCO_L072CZ_LRWAN1/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/DISCO_L475VG_IOT/PinNamesVar.h b/variants/DISCO_L475VG_IOT/PinNamesVar.h
new file mode 100644
index 0000000000..c4331ecd62
--- /dev/null
+++ b/variants/DISCO_L475VG_IOT/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = PE_6,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = PA_2,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = PC_5,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/DISCO_L475VG_IOT/variant.cpp b/variants/DISCO_L475VG_IOT/variant.cpp
index fdc4cf817b..5cb3111860 100644
--- a/variants/DISCO_L475VG_IOT/variant.cpp
+++ b/variants/DISCO_L475VG_IOT/variant.cpp
@@ -173,17 +173,17 @@ WEAK void SystemClock_Config(void)
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_MSI;
RCC_OscInitStruct.MSIState = RCC_MSI_ON;
RCC_OscInitStruct.MSICalibrationValue = 0;
- RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_11;
+ RCC_OscInitStruct.MSIClockRange = RCC_MSIRANGE_6;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_MSI;
- RCC_OscInitStruct.PLL.PLLM = 6;
+ RCC_OscInitStruct.PLL.PLLM = 1;
RCC_OscInitStruct.PLL.PLLN = 40;
RCC_OscInitStruct.PLL.PLLP = 7;
- RCC_OscInitStruct.PLL.PLLQ = 4;
- RCC_OscInitStruct.PLL.PLLR = 4;
+ RCC_OscInitStruct.PLL.PLLQ = 2;
+ RCC_OscInitStruct.PLL.PLLR = 2;
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
{
- while(1);
+ Error_Handler();
}
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
@@ -195,29 +195,42 @@ WEAK void SystemClock_Config(void)
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_4) != HAL_OK)
{
- while(1);
+ Error_Handler();
}
- PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_UART4
- |RCC_PERIPHCLK_I2C1|RCC_PERIPHCLK_I2C2
+ PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2
+ |RCC_PERIPHCLK_USART3|RCC_PERIPHCLK_UART4
+ |RCC_PERIPHCLK_UART5|RCC_PERIPHCLK_I2C1
+ |RCC_PERIPHCLK_I2C2|RCC_PERIPHCLK_DFSDM1
|RCC_PERIPHCLK_USB|RCC_PERIPHCLK_ADC;
+ PeriphClkInit.Usart1ClockSelection = RCC_USART1CLKSOURCE_PCLK2;
PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
+ PeriphClkInit.Usart3ClockSelection = RCC_USART3CLKSOURCE_PCLK1;
PeriphClkInit.Uart4ClockSelection = RCC_UART4CLKSOURCE_PCLK1;
+ PeriphClkInit.Uart5ClockSelection = RCC_UART5CLKSOURCE_PCLK1;
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_PCLK1;
PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1;
PeriphClkInit.AdcClockSelection = RCC_ADCCLKSOURCE_SYSCLK;
- PeriphClkInit.UsbClockSelection = RCC_USBCLKSOURCE_MSI;
+ 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)
{
- while(1);
+ Error_Handler();
}
/**Configure the main internal regulator output voltage
*/
if (HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1) != HAL_OK)
{
- while(1);
+ Error_Handler();
}
/**Configure the Systick interrupt time
diff --git a/variants/MAPLEMINI_F103CB/PinNamesVar.h b/variants/MAPLEMINI_F103CB/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/MAPLEMINI_F103CB/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/MAPLEMINI_F103CB/stm32f1xx_hal_conf.h b/variants/MAPLEMINI_F103CB/stm32f1xx_hal_conf.h
index 9369936ed5..b466615b2f 100644
--- a/variants/MAPLEMINI_F103CB/stm32f1xx_hal_conf.h
+++ b/variants/MAPLEMINI_F103CB/stm32f1xx_hal_conf.h
@@ -70,7 +70,7 @@
/*#define HAL_NOR_MODULE_ENABLED*/
/*#define HAL_PCCARD_MODULE_ENABLED*/
/*#define HAL_PCD_MODULE_ENABLED*/
-/*#define HAL_PWR_MODULE_ENABLED*/
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
/*#define HAL_SD_MODULE_ENABLED*/
diff --git a/variants/NUCLEO_F030R8/PinNamesVar.h b/variants/NUCLEO_F030R8/PinNamesVar.h
new file mode 100644
index 0000000000..0b7fa5cc33
--- /dev/null
+++ b/variants/NUCLEO_F030R8/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F030R8/stm32f0xx_hal_conf.h b/variants/NUCLEO_F030R8/stm32f0xx_hal_conf.h
index d455dc3986..31cbb5dc00 100644
--- a/variants/NUCLEO_F030R8/stm32f0xx_hal_conf.h
+++ b/variants/NUCLEO_F030R8/stm32f0xx_hal_conf.h
@@ -66,7 +66,7 @@
//#define HAL_IRDA_MODULE_ENABLED
//#define HAL_IWDG_MODULE_ENABLED
//#define HAL_PCD_MODULE_ENABLED
-//#define HAL_PWR_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
//#define HAL_SMARTCARD_MODULE_ENABLED
diff --git a/variants/NUCLEO_F091RC/PinNamesVar.h b/variants/NUCLEO_F091RC/PinNamesVar.h
new file mode 100644
index 0000000000..ec995a0089
--- /dev/null
+++ b/variants/NUCLEO_F091RC/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = PE_6, /* manually updated */
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = PA_2,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = PC_5,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = PB_5,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = PB_15,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = PF_2, /* manually updated */
+#endif
diff --git a/variants/NUCLEO_F091RC/stm32f0xx_hal_conf.h b/variants/NUCLEO_F091RC/stm32f0xx_hal_conf.h
index c7c47dcb91..45a08eabe7 100644
--- a/variants/NUCLEO_F091RC/stm32f0xx_hal_conf.h
+++ b/variants/NUCLEO_F091RC/stm32f0xx_hal_conf.h
@@ -66,7 +66,7 @@
//#define HAL_IRDA_MODULE_ENABLED
//#define HAL_IWDG_MODULE_ENABLED
//#define HAL_PCD_MODULE_ENABLED
-//#define HAL_PWR_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
//#define HAL_SMARTCARD_MODULE_ENABLED
diff --git a/variants/NUCLEO_F103RB/PinNamesVar.h b/variants/NUCLEO_F103RB/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/NUCLEO_F103RB/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F103RB/stm32f1xx_hal_conf.h b/variants/NUCLEO_F103RB/stm32f1xx_hal_conf.h
index 9369936ed5..b466615b2f 100644
--- a/variants/NUCLEO_F103RB/stm32f1xx_hal_conf.h
+++ b/variants/NUCLEO_F103RB/stm32f1xx_hal_conf.h
@@ -70,7 +70,7 @@
/*#define HAL_NOR_MODULE_ENABLED*/
/*#define HAL_PCCARD_MODULE_ENABLED*/
/*#define HAL_PCD_MODULE_ENABLED*/
-/*#define HAL_PWR_MODULE_ENABLED*/
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
/*#define HAL_SD_MODULE_ENABLED*/
diff --git a/variants/NUCLEO_F207ZG/PinNamesVar.h b/variants/NUCLEO_F207ZG/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/NUCLEO_F207ZG/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F302R8/PinNamesVar.h b/variants/NUCLEO_F302R8/PinNamesVar.h
new file mode 100644
index 0000000000..0b7fa5cc33
--- /dev/null
+++ b/variants/NUCLEO_F302R8/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F302R8/stm32f3xx_hal_conf.h b/variants/NUCLEO_F302R8/stm32f3xx_hal_conf.h
index 9585e0e819..39ab432930 100644
--- a/variants/NUCLEO_F302R8/stm32f3xx_hal_conf.h
+++ b/variants/NUCLEO_F302R8/stm32f3xx_hal_conf.h
@@ -72,7 +72,7 @@
// #define HAL_IWDG_MODULE_ENABLED
// #define HAL_OPAMP_MODULE_ENABLED
// #define HAL_PCD_MODULE_ENABLED
-// #define HAL_PWR_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
// #define HAL_SDADC_MODULE_ENABLED
diff --git a/variants/NUCLEO_F303K8/PinNamesVar.h b/variants/NUCLEO_F303K8/PinNamesVar.h
new file mode 100644
index 0000000000..51e79ef6a5
--- /dev/null
+++ b/variants/NUCLEO_F303K8/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13, /* manually updated */
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F303RE/PinNamesVar.h b/variants/NUCLEO_F303RE/PinNamesVar.h
new file mode 100644
index 0000000000..45099dfe6c
--- /dev/null
+++ b/variants/NUCLEO_F303RE/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = PE_6, /* manually updated */
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F303RE/stm32f3xx_hal_conf.h b/variants/NUCLEO_F303RE/stm32f3xx_hal_conf.h
index 3a09bb6299..ecb7c07a8d 100644
--- a/variants/NUCLEO_F303RE/stm32f3xx_hal_conf.h
+++ b/variants/NUCLEO_F303RE/stm32f3xx_hal_conf.h
@@ -72,7 +72,7 @@
// #define HAL_IWDG_MODULE_ENABLED
// #define HAL_OPAMP_MODULE_ENABLED
// #define HAL_PCD_MODULE_ENABLED
-// #define HAL_PWR_MODULE_ENABLED
+#define HAL_PWR_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED
#define HAL_RTC_MODULE_ENABLED
// #define HAL_SDADC_MODULE_ENABLED
diff --git a/variants/NUCLEO_F401RE/PinNamesVar.h b/variants/NUCLEO_F401RE/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/NUCLEO_F401RE/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F411RE/PinNamesVar.h b/variants/NUCLEO_F411RE/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/NUCLEO_F411RE/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F429ZI/PinNamesVar.h b/variants/NUCLEO_F429ZI/PinNamesVar.h
new file mode 100644
index 0000000000..b65ff1991e
--- /dev/null
+++ b/variants/NUCLEO_F429ZI/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_F446RE/PinNamesVar.h b/variants/NUCLEO_F446RE/PinNamesVar.h
new file mode 100644
index 0000000000..3acc637167
--- /dev/null
+++ b/variants/NUCLEO_F446RE/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0, /* SYS_WKUP0 */
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13, /* SYS_WKUP1 */
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_L031K6/PinNamesVar.h b/variants/NUCLEO_L031K6/PinNamesVar.h
new file mode 100644
index 0000000000..43ae409097
--- /dev/null
+++ b/variants/NUCLEO_L031K6/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = PA_2,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_L053R8/PinNamesVar.h b/variants/NUCLEO_L053R8/PinNamesVar.h
new file mode 100644
index 0000000000..0b7fa5cc33
--- /dev/null
+++ b/variants/NUCLEO_L053R8/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_L152RE/PinNamesVar.h b/variants/NUCLEO_L152RE/PinNamesVar.h
new file mode 100644
index 0000000000..0b7fa5cc33
--- /dev/null
+++ b/variants/NUCLEO_L152RE/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_L432KC/PinNamesVar.h b/variants/NUCLEO_L432KC/PinNamesVar.h
new file mode 100644
index 0000000000..43ca21646a
--- /dev/null
+++ b/variants/NUCLEO_L432KC/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13, /* manually updated */
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = PA_2,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = PC_5, /* manually updated */
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif
diff --git a/variants/NUCLEO_L476RG/PinNamesVar.h b/variants/NUCLEO_L476RG/PinNamesVar.h
new file mode 100644
index 0000000000..f712d8ac24
--- /dev/null
+++ b/variants/NUCLEO_L476RG/PinNamesVar.h
@@ -0,0 +1,25 @@
+ /* SYS_WKUP */
+#ifdef PWR_WAKEUP_PIN1
+ SYS_WKUP1 = PA_0,
+#endif
+#ifdef PWR_WAKEUP_PIN2
+ SYS_WKUP2 = PC_13,
+#endif
+#ifdef PWR_WAKEUP_PIN3
+ SYS_WKUP3 = PE_6, /* manually updated */
+#endif
+#ifdef PWR_WAKEUP_PIN4
+ SYS_WKUP4 = PA_2,
+#endif
+#ifdef PWR_WAKEUP_PIN5
+ SYS_WKUP5 = PC_5,
+#endif
+#ifdef PWR_WAKEUP_PIN6
+ SYS_WKUP6 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN7
+ SYS_WKUP7 = NC,
+#endif
+#ifdef PWR_WAKEUP_PIN8
+ SYS_WKUP8 = NC,
+#endif