You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@nuttx.apache.org by ac...@apache.org on 2020/02/29 15:22:23 UTC

[incubator-nuttx] branch pr402 updated (e309128 -> 17985a2)

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

acassis pushed a change to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git.


    from e309128  boards/z80/ez80/z20x/README.txt:  Update README.
     new 8bb803e  STM32H7 ADC1 and ADC2 share some common registers.  Added mbase and associated functions to driver to account for this.
     new 0bfb680  STM32H7: Only reset ADC1/2 if the other one has not already been reset.
     new 693e16c  STM32H7: stm32_ethinitialize should not be static if CONFIG_NETDEV_LATEINIT is defined.
     new ac654d9  Added basic power management (sleep/stop/standby) for STM32H7
     new a7c5016  Added basic support for IWDG and WWDG to STM32H7
     new e405e59  Handle case where only ADC1 or ADC2 is enabled.
     new 5d2b433  Fix PCSEL setup on STM32H7 ADC
     new 71be7d7  Added support for configuring WKUP pins on STM32H7.
     new dad5d68  Fixed some issues with internal flash driver on STM32H7
     new f7577e2  Updated STM32H7 startup with check for ACTVOSRDY per recommendation in reference manual.
     new 115ccf5  Fixed compiler warning about possibly uninitialized variable.
     new 96cec9c  Added configuration function for onboard VBAT charger in STM32H7
     new 17985a2  Clean up comments and formatting

The 13 revisions listed above as "new" are entirely new to this
repository and will be described in separate emails.  The revisions
listed as "add" were already present in the repository and have only
been added to this reference.


Summary of changes:
 arch/arm/src/stm32h7/Kconfig                       |  10 +
 arch/arm/src/stm32h7/Make.defs                     |  15 ++
 .../src/{stm32 => stm32h7}/hardware/stm32_wdg.h    |  30 ++-
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h  |  16 +-
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h    | 254 +++++++++++++--------
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_rcc.h    |  20 +-
 arch/arm/src/stm32h7/stm32_adc.c                   | 136 +++++++++--
 arch/arm/src/stm32h7/stm32_ethernet.c              |  73 +++---
 arch/arm/src/stm32h7/stm32_ethernet.h              |   6 +-
 arch/arm/src/stm32h7/stm32_flash.c                 | 201 +++++++++++++---
 .../{tms570/tms570_esm.h => stm32h7/stm32_flash.h} |  36 +--
 arch/arm/src/{stm32 => stm32h7}/stm32_iwdg.c       | 117 +++++-----
 arch/arm/src/{stm32f7 => stm32h7}/stm32_pm.h       |  20 +-
 .../src/{stm32 => stm32h7}/stm32_pminitialize.c    |   4 +-
 arch/arm/src/{stm32f7 => stm32h7}/stm32_pmsleep.c  |   8 +-
 .../arm/src/{stm32f7 => stm32h7}/stm32_pmstandby.c |  22 +-
 arch/arm/src/{stm32f7 => stm32h7}/stm32_pmstop.c   |  44 ++--
 arch/arm/src/stm32h7/stm32_pwr.c                   | 130 ++++++++++-
 arch/arm/src/stm32h7/stm32_pwr.h                   |  56 ++++-
 arch/arm/src/{stm32 => stm32h7}/stm32_wdg.h        |  16 +-
 arch/arm/src/{stm32 => stm32h7}/stm32_wwdg.c       | 119 +++++-----
 arch/arm/src/stm32h7/stm32h7x3xx_rcc.c             |  22 +-
 22 files changed, 935 insertions(+), 420 deletions(-)
 copy arch/arm/src/{stm32 => stm32h7}/hardware/stm32_wdg.h (88%)
 copy arch/arm/src/{tms570/tms570_esm.h => stm32h7/stm32_flash.h} (76%)
 copy arch/arm/src/{stm32 => stm32h7}/stm32_iwdg.c (86%)
 copy arch/arm/src/{stm32f7 => stm32h7}/stm32_pm.h (90%)
 copy arch/arm/src/{stm32 => stm32h7}/stm32_pminitialize.c (96%)
 copy arch/arm/src/{stm32f7 => stm32h7}/stm32_pmsleep.c (94%)
 copy arch/arm/src/{stm32f7 => stm32h7}/stm32_pmstandby.c (79%)
 copy arch/arm/src/{stm32f7 => stm32h7}/stm32_pmstop.c (74%)
 copy arch/arm/src/{stm32 => stm32h7}/stm32_wdg.h (91%)
 copy arch/arm/src/{stm32 => stm32h7}/stm32_wwdg.c (88%)


[incubator-nuttx] 02/13: STM32H7: Only reset ADC1/2 if the other one has not already been reset.

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 0bfb6803f2038a5b7af4f906ab4f7873f2291fff
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Thu Jan 23 13:41:39 2020 -0600

    STM32H7: Only reset ADC1/2 if the other one has not already been reset.
---
 arch/arm/src/stm32h7/stm32_adc.c | 21 +++++++++++++++++++--
 1 file changed, 19 insertions(+), 2 deletions(-)

diff --git a/arch/arm/src/stm32h7/stm32_adc.c b/arch/arm/src/stm32h7/stm32_adc.c
index 9e758af..854034f 100644
--- a/arch/arm/src/stm32h7/stm32_adc.c
+++ b/arch/arm/src/stm32h7/stm32_adc.c
@@ -175,6 +175,7 @@ struct stm32_dev_s
                          * block */
   uint32_t mbase;       /* Base address of master ADC (allows for access to
                            shared common registers) */
+  bool     initialized; /* Keeps track of the initialization status of the ADC */
 #ifdef ADC_HAVE_TIMER
   uint32_t tbase;       /* Base address of timer used by this ADC block */
   uint32_t trcc_enr;    /* RCC ENR Register */
@@ -300,6 +301,7 @@ static struct stm32_dev_s g_adcpriv1 =
   .intf        = 1,
   .base        = STM32_ADC1_BASE,
   .mbase       = STM32_ADC1_BASE,
+  .initialized = false,
 #ifdef ADC1_HAVE_TIMER
   .trigger     = CONFIG_STM32H7_ADC1_TIMTRIG,
   .tbase       = ADC1_TIMER_BASE,
@@ -341,6 +343,7 @@ static struct stm32_dev_s g_adcpriv2 =
   .intf        = 2,
   .base        = STM32_ADC2_BASE,
   .mbase       = STM32_ADC1_BASE,
+  .initialized = false,
 #ifdef ADC2_HAVE_TIMER
   .trigger     = CONFIG_STM32H7_ADC2_TIMTRIG,
   .tbase       = ADC2_TIMER_BASE,
@@ -382,6 +385,7 @@ static struct stm32_dev_s g_adcpriv3 =
   .intf        = 3,
   .base        = STM32_ADC3_BASE,
   .mbase       = STM32_ADC3_BASE,
+  .initialized = false,
 #ifdef ADC3_HAVE_TIMER
   .trigger     = CONFIG_STM32H7_ADC3_TIMTRIG,
   .tbase       = ADC3_TIMER_BASE,
@@ -1323,9 +1327,18 @@ static int adc_setup(FAR struct adc_dev_s *dev)
 
   flags = enter_critical_section();
 
-  /* Make sure that the ADC device is in the powered up, reset state. */
+  /* Make sure that the ADC device is in the powered up, reset state.
+   * Since reset is shared between ADC1 and ADC2, don't reset one if the
+   * other has already been reset.
+   */
 
-  adc_reset(dev);
+  if ((dev == &g_adcdev1 &&
+      !((FAR struct stm32_dev_s *)g_adcdev2.ad_priv)->initialized) ||
+     (dev == &g_adcdev2 &&
+      !((FAR struct stm32_dev_s *)g_adcdev1.ad_priv)->initialized))
+  {
+     adc_reset(dev);
+  }
 
   /* Initialize the same sample time for each ADC.
    * During sample cycles channel selection bits must remain unchanged.
@@ -1467,6 +1480,8 @@ static int adc_setup(FAR struct adc_dev_s *dev)
   ainfo("Enable the ADC interrupt: irq=%d\n", priv->irq);
   up_enable_irq(priv->irq);
 
+  priv->initialized = true;
+
   return ret;
 }
 
@@ -1499,6 +1514,8 @@ static void adc_shutdown(FAR struct adc_dev_s *dev)
   /* Disable and reset the ADC module */
 
   adc_reset(dev);
+
+  priv->initialized = false;
 }
 
 /****************************************************************************


[incubator-nuttx] 09/13: Fixed some issues with internal flash driver on STM32H7

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit dad5d6865d88fc42648d762b861d3e5c783d430f
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Tue Feb 18 19:03:07 2020 -0600

    Fixed some issues with internal flash driver on STM32H7
---
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h |   2 +-
 arch/arm/src/stm32h7/stm32_flash.c                | 141 +++++++++++++++++++++-
 arch/arm/src/stm32h7/stm32_flash.h                | 100 +++++++++++++++
 3 files changed, 236 insertions(+), 7 deletions(-)

diff --git a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h
index 3de570d..976c67a 100644
--- a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h
+++ b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h
@@ -168,7 +168,7 @@
 #define FLASH_CR_START                 (1 << 7)   /* Bit 7: Erase start */
 #define FLASH_CR_SNB_SHIFT             (8)        /* Bits 8-10: Sector number */
 #define FLASH_CR_SNB_MASK              (15 << FLASH_CR_SNB_SHIFT)  /* Used to clear FLASH_CR_SNB bits */
-#  define FLASH_CR_SNB(n)              ((uint32_t)(n & 0x7) << FLASH_CR_SNB_SHIFT) /* Sector n, n=0..7 */
+#  define FLASH_CR_SNB(n)              ((uint32_t)((n) & 0x7) << FLASH_CR_SNB_SHIFT) /* Sector n, n=0..7 */
                                                   /* Bits 11-13: Reserved */
 #define FLASH_CR_SPSS2                 (1 << 14)  /* Bit 14: Bank1 Reserved, Bank 2 special sector selection bit */
 #define FLASH_CR_CRCEN                 (1 << 15)  /* Bit 15: CRC control enable */
diff --git a/arch/arm/src/stm32h7/stm32_flash.c b/arch/arm/src/stm32h7/stm32_flash.c
index e676697..0881eac 100644
--- a/arch/arm/src/stm32h7/stm32_flash.c
+++ b/arch/arm/src/stm32h7/stm32_flash.c
@@ -193,7 +193,7 @@ static struct stm32h7_flash_priv_s stm32h7_flash_bank2_priv =
  *****************************************************************************/
 
 static inline uint32_t stm32h7_flash_getreg32(FAR struct stm32h7_flash_priv_s
-                                            *priv, uint8_t offset)
+                                            *priv, uint32_t offset)
 {
   return getreg32(priv->ifbase + offset);
 }
@@ -207,7 +207,7 @@ static inline uint32_t stm32h7_flash_getreg32(FAR struct stm32h7_flash_priv_s
  ****************************************************************************/
 
 static inline void stm32h7_flash_putreg32(FAR struct stm32h7_flash_priv_s
-                                          *priv, uint8_t offset,
+                                          *priv, uint32_t offset,
                                           uint32_t value)
 {
   putreg32(value, priv->ifbase + offset);
@@ -222,7 +222,7 @@ static inline void stm32h7_flash_putreg32(FAR struct stm32h7_flash_priv_s
  *****************************************************************************/
 
 static inline void stm32h7_flash_modifyreg32(FAR struct stm32h7_flash_priv_s
-                                             *priv, uint8_t offset,
+                                             *priv, uint32_t offset,
                                              uint32_t clearbits,
                                              uint32_t setbits)
 {
@@ -330,6 +330,73 @@ FAR struct stm32h7_flash_priv_s * stm32h7_flash_bank(size_t address)
   return priv;
 }
 
+/*****************************************************************************
+ * Name: stm32h7_unlock_flashopt
+ *
+ * Description:
+ *   Unlock the flash option bytes
+ *
+ *****************************************************************************/
+
+static void stm32h7_unlock_flashopt(FAR struct stm32h7_flash_priv_s *priv)
+{
+  while (stm32h7_flash_getreg32(priv, STM32_FLASH_SR1_OFFSET) & FLASH_SR_BSY)
+    {
+    }
+
+  if (stm32h7_flash_getreg32(priv, STM32_FLASH_OPTCR_OFFSET) & FLASH_OPTCR_OPTLOCK)
+    {
+      /* Unlock sequence */
+
+      stm32h7_flash_putreg32(priv, STM32_FLASH_OPTKEYR_OFFSET, FLASH_OPTKEY1);
+      stm32h7_flash_putreg32(priv, STM32_FLASH_OPTKEYR_OFFSET, FLASH_OPTKEY2);
+    }
+}
+
+/*****************************************************************************
+ * Name: stm32h7_lock_flashopt
+ *
+ * Description:
+ *   Lock the flash option bytes
+ *
+ *****************************************************************************/
+
+static void stm32h7_lock_flashopt(FAR struct stm32h7_flash_priv_s *priv)
+{
+  stm32h7_flash_modifyreg32(priv, STM32_FLASH_OPTCR_OFFSET, 0, FLASH_OPTCR_OPTLOCK);
+}
+
+/*****************************************************************************
+ * Name: stm32h7_save_flashopt
+ *
+ * Description:
+ *   Save the flash option bytes to non-volatile storage.
+ *
+ *****************************************************************************/
+
+static void stm32h7_save_flashopt(FAR struct stm32h7_flash_priv_s *priv)
+{
+  while (stm32h7_flash_getreg32(priv, STM32_FLASH_SR1_OFFSET) &
+        (FLASH_SR_BSY | FLASH_SR_CRCBUSY))
+    {
+    }
+  while (stm32h7_flash_getreg32(priv, STM32_FLASH_SR2_OFFSET) &
+        (FLASH_SR_BSY | FLASH_SR_CRCBUSY))
+    {
+    }
+
+  /* Can only write flash options if the option control reg is unlocked */
+  if (!(stm32h7_flash_getreg32(priv, STM32_FLASH_OPTCR_OFFSET) & FLASH_OPTCR_OPTLOCK))
+    {
+      stm32h7_flash_modifyreg32(priv, STM32_FLASH_OPTCR_OFFSET, 0, FLASH_OPTCR_OPTSTRT);
+    }
+
+  /* Wait for the update to complete */
+  while (stm32h7_flash_getreg32(priv, STM32_FLASH_OPTSR_CUR_OFFSET) & FLASH_OPTSR_BUSYV)
+    {
+    }
+}
+
 /****************************************************************************
  * Public Functions
  ****************************************************************************/
@@ -423,6 +490,67 @@ int stm32h7_flash_writeprotect(size_t block, bool enabled)
   return rv;
 }
 
+/****************************************************************************
+ * Name: stm32h7_flash_getopt
+ *
+ * Description:
+ *   Returns the current flash option bytes from the FLASH_OPTSR_CR register.
+ *
+ ****************************************************************************/
+
+uint32_t stm32h7_flash_getopt(void)
+{
+  struct stm32h7_flash_priv_s *priv;
+  priv = stm32h7_flash_bank(STM32_FLASH_BANK1);
+  if (priv)
+    {
+      return stm32h7_flash_getreg32(priv, STM32_FLASH_OPTSR_CUR_OFFSET);
+    }
+  return 0;
+}
+
+/****************************************************************************
+ * Name: stm32h7_flash_optmodify
+ *
+ * Description:
+ *   Modifies the current flash option bytes, given bits to set and clear.
+ *
+ ****************************************************************************/
+
+void stm32h7_flash_optmodify(uint32_t clear, uint32_t set)
+{
+  struct stm32h7_flash_priv_s *priv;
+  priv = stm32h7_flash_bank(STM32_FLASH_BANK1);
+  if (priv)
+    {
+    stm32h7_unlock_flashopt(priv);
+    stm32h7_flash_modifyreg32(priv, STM32_FLASH_OPTSR_PRG_OFFSET, clear, set);
+    stm32h7_save_flashopt(priv);
+  }
+}
+
+/****************************************************************************
+ * Name: stm32h7_flash_swapbanks
+ *
+ * Description:
+ *   Swaps banks 1 and 2 in the processor's memory map.  Takes effect
+ *   the next time the system is reset.
+ *
+ ****************************************************************************/
+
+void stm32h7_flash_swapbanks(void)
+{
+  uint32_t opts = stm32h7_flash_getopt();
+  if (opts & FLASH_OPTCR_SWAPBANK)
+    {
+      stm32h7_flash_optmodify(FLASH_OPTCR_SWAPBANK, 0);
+    }
+  else
+    {
+      stm32h7_flash_optmodify(0, FLASH_OPTCR_SWAPBANK);
+    }
+}
+
 size_t up_progmem_pagesize(size_t page)
 {
   return FLASH_SECTOR_SIZE;
@@ -508,11 +636,12 @@ ssize_t up_progmem_eraseblock(size_t block)
 
   stm32h7_flash_modifyreg32(priv, STM32_FLASH_CR1_OFFSET, 0, FLASH_CR_SER);
   stm32h7_flash_modifyreg32(priv, STM32_FLASH_CR1_OFFSET, FLASH_CR_SNB_MASK,
-                            FLASH_CR_SNB(block));
+                            FLASH_CR_SNB(block - priv->stblock));
 
   stm32h7_flash_modifyreg32(priv, STM32_FLASH_CR1_OFFSET, 0, FLASH_CR_START);
 
-  while (stm32h7_flash_getreg32(priv, STM32_FLASH_CR1_OFFSET) & FLASH_SR_BSY)
+  while (stm32h7_flash_getreg32(priv, STM32_FLASH_SR1_OFFSET) &
+        (FLASH_SR_BSY | FLASH_SR_QW))
     {
     }
 
@@ -600,7 +729,7 @@ ssize_t up_progmem_write(size_t addr, const void *buf, size_t count)
       ARM_ISB();
 
       while (stm32h7_flash_getreg32(priv, STM32_FLASH_SR1_OFFSET) &
-             FLASH_SR_BSY)
+             (FLASH_SR_BSY | FLASH_SR_QW))
         {
         }
 
diff --git a/arch/arm/src/stm32h7/stm32_flash.h b/arch/arm/src/stm32h7/stm32_flash.h
new file mode 100644
index 0000000..ca2696a
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_flash.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_fflash.h
+ *
+ *   Copyright (C) 2020 Gregory Nutt. All rights reserved.
+ *   Author: Joshua Lange <jl...@2g-eng.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32H7_STM32_FLASH_H
+#define __ARCH_ARM_SRC_STM32H7_STM32_FLASH_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "hardware/stm32_flash.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Name: stm32h7_flash_getopt
+ *
+ * Description:
+ *   Returns the current flash option bytes from the FLASH_OPTSR_CR register.
+ *
+ ****************************************************************************/
+
+uint32_t stm32h7_flash_getopt(void);
+
+/****************************************************************************
+ * Name: stm32h7_flash_optmodify
+ *
+ * Description:
+ *   Modifies the current flash option bytes, given bits to set and clear.
+ *
+ ****************************************************************************/
+
+void stm32h7_flash_optmodify(uint32_t clear, uint32_t set);
+
+/****************************************************************************
+ * Name: stm32h7_flash_swapbanks
+ *
+ * Description:
+ *   Swaps banks 1 and 2 in the processor's memory map.  Takes effect
+ *   the next time the system is reset.
+ *
+ ****************************************************************************/
+
+void stm32h7_flash_swapbanks(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_STM32H7_STM32_FLASH_H */


[incubator-nuttx] 03/13: STM32H7: stm32_ethinitialize should not be static if CONFIG_NETDEV_LATEINIT is defined.

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 693e16c3ce710c7a02fa73a5d01a2ed17c862e8b
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Thu Jan 23 13:47:13 2020 -0600

    STM32H7: stm32_ethinitialize should not be static if CONFIG_NETDEV_LATEINIT is defined.
---
 arch/arm/src/stm32h7/stm32_ethernet.c | 8 ++++----
 arch/arm/src/stm32h7/stm32_ethernet.h | 2 +-
 2 files changed, 5 insertions(+), 5 deletions(-)

diff --git a/arch/arm/src/stm32h7/stm32_ethernet.c b/arch/arm/src/stm32h7/stm32_ethernet.c
index d9903cf..e2002f8 100644
--- a/arch/arm/src/stm32h7/stm32_ethernet.c
+++ b/arch/arm/src/stm32h7/stm32_ethernet.c
@@ -4328,11 +4328,11 @@ static int stm32_ethconfig(struct stm32_ethmac_s *priv)
  *
  ****************************************************************************/
 
-#if STM32H7_NETHERNET == 1 || defined(CONFIG_NETDEV_LATEINIT)
-static inline
-#endif
-
+#if STM32H7_NETHERNET > 1 || defined(CONFIG_NETDEV_LATEINIT)
 int stm32_ethinitialize(int intf)
+#else
+static inline int stm32_ethinitialize(int intf)
+#endif
 {
   struct stm32_ethmac_s *priv;
 
diff --git a/arch/arm/src/stm32h7/stm32_ethernet.h b/arch/arm/src/stm32h7/stm32_ethernet.h
index fdb1ad5..92da890 100644
--- a/arch/arm/src/stm32h7/stm32_ethernet.h
+++ b/arch/arm/src/stm32h7/stm32_ethernet.h
@@ -80,7 +80,7 @@ extern "C"
  *
  ****************************************************************************/
 
-#if STM32H7_NETHERNET > 1
+#if STM32H7_NETHERNET > 1 || defined(CONFIG_NETDEV_LATEINIT)
 int stm32_ethinitialize(int intf);
 #endif
 


[incubator-nuttx] 08/13: Added support for configuring WKUP pins on STM32H7.

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 71be7d7540f07dec28a5eb71216fe5ad064e9da4
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Mon Feb 17 13:14:32 2020 -0600

    Added support for configuring WKUP pins on STM32H7.
---
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h | 262 ++++++++++++------------
 arch/arm/src/stm32h7/stm32_pwr.c                |  69 ++++++-
 arch/arm/src/stm32h7/stm32_pwr.h                |  23 +++
 3 files changed, 224 insertions(+), 130 deletions(-)

diff --git a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
index 3c84e6b..647dbf7 100644
--- a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
+++ b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
@@ -43,170 +43,174 @@
 
 /* Register Offsets *****************************************************************/
 
-#define STM32_PWR_CR1_OFFSET     0x0000  /* Power control register 1 */
-#define STM32_PWR_CSR1_OFFSET    0x0004  /* Power control/status register 1 */
-#define STM32_PWR_CR2_OFFSET     0x0008  /* Power control register 2 */
-#define STM32_PWR_CR3_OFFSET     0x000c  /* Power control register 3 */
-#define STM32_PWR_CPUCR_OFFSET   0x0010  /* Power CPU control register */
-                                         /* 0x014: Reserved */
-#define STM32_PWR_D3CR_OFFSET    0x0018  /* Power D3 domain control register */
-#define STM32_PWR_WKUPCR_OFFSET  0x0020  /* Power wakeup clear register */
-#define STM32_PWR_WKUPFR_OFFSET  0x0024  /* Power wakeup flag register */
-#define STM32_PWR_WKUPEPR_OFFSET 0x0028  /* Power wakeup enable and polarity register*/
-                                         /* 0x030: Reserved */
+#define STM32_PWR_CR1_OFFSET        0x0000  /* Power control register 1 */
+#define STM32_PWR_CSR1_OFFSET       0x0004  /* Power control/status register 1 */
+#define STM32_PWR_CR2_OFFSET        0x0008  /* Power control register 2 */
+#define STM32_PWR_CR3_OFFSET        0x000c  /* Power control register 3 */
+#define STM32_PWR_CPUCR_OFFSET      0x0010  /* Power CPU control register */
+                                            /* 0x014: Reserved */
+#define STM32_PWR_D3CR_OFFSET       0x0018  /* Power D3 domain control register */
+#define STM32_PWR_WKUPCR_OFFSET     0x0020  /* Power wakeup clear register */
+#define STM32_PWR_WKUPFR_OFFSET     0x0024  /* Power wakeup flag register */
+#define STM32_PWR_WKUPEPR_OFFSET    0x0028  /* Power wakeup enable and polarity register*/
+                                          /* 0x030: Reserved */
 
 /* Register Addresses ***************************************************************/
 
-#define STM32_PWR_CR1            (STM32_PWR_BASE+STM32_PWR_CR1_OFFSET)
-#define STM32_PWR_CSR1           (STM32_PWR_BASE+STM32_PWR_CSR1_OFFSET)
-#define STM32_PWR_CR2            (STM32_PWR_BASE+STM32_PWR_CR2_OFFSET)
-#define STM32_PWR_CR3            (STM32_PWR_BASE+STM32_PWR_CR3_OFFSET)
-#define STM32_PWR_CPUCR          (STM32_PWR_BASE+STM32_PWR_CPUCR_OFFSET)
-#define STM32_PWR_D3CR           (STM32_PWR_BASE+STM32_PWR_D3CR_OFFSET)
-#define STM32_PWR_WKUPCR         (STM32_PWR_BASE+STM32_PWR_WKUPCR_OFFSET)
-#define STM32_PWR_WKUPFR         (STM32_PWR_BASE+STM32_PWR_WKUPFR_OFFSET)
-#define STM32_PWR_WKUPEOR        (STM32_PWR_BASE+STM32_PWR_WKUPEOR_OFFSET)
+#define STM32_PWR_CR1               (STM32_PWR_BASE+STM32_PWR_CR1_OFFSET)
+#define STM32_PWR_CSR1              (STM32_PWR_BASE+STM32_PWR_CSR1_OFFSET)
+#define STM32_PWR_CR2               (STM32_PWR_BASE+STM32_PWR_CR2_OFFSET)
+#define STM32_PWR_CR3               (STM32_PWR_BASE+STM32_PWR_CR3_OFFSET)
+#define STM32_PWR_CPUCR             (STM32_PWR_BASE+STM32_PWR_CPUCR_OFFSET)
+#define STM32_PWR_D3CR              (STM32_PWR_BASE+STM32_PWR_D3CR_OFFSET)
+#define STM32_PWR_WKUPCR            (STM32_PWR_BASE+STM32_PWR_WKUPCR_OFFSET)
+#define STM32_PWR_WKUPFR            (STM32_PWR_BASE+STM32_PWR_WKUPFR_OFFSET)
+#define STM32_PWR_WKUPEOR           (STM32_PWR_BASE+STM32_PWR_WKUPEOR_OFFSET)
 
 /* Register Bitfield Definitions ****************************************************/
 
 /* Power control register 1 (CR1) */
 
-#define PWR_CR1_LPDS             (1 << 0)    /* Bit 0: Low-power Deepsleep with SVOS3 */
-                                             /* Bits 1-3: Reserved */
-#define PWR_CR1_PVDE             (1 << 4)    /* Bit 4: Programmable voltage detector enable */
-
-
-#define PWR_CR1_PLS_SHIFT         (5)        /* Bits 5-7: Programmable voltage detector level */
-#define PWR_CR1_PLS_MASK          (7 << PWR_CR1_PLS_SHIFT)
-#  define PWR_CR1_PLS_1V95        (0 << PWR_CR1_PLS_SHIFT) /* 000: */
-#  define PWR_CR1_PLS_2V1         (1 << PWR_CR1_PLS_SHIFT) /* 001: */
-#  define PWR_CR1_PLS_2V25        (2 << PWR_CR1_PLS_SHIFT) /* 010: */
-#  define PWR_CR1_PLS_2V4         (3 << PWR_CR1_PLS_SHIFT) /* 011: */
-#  define PWR_CR1_PLS_2V55        (4 << PWR_CR1_PLS_SHIFT) /* 100: */
-#  define PWR_CR1_PLS_2V7         (5 << PWR_CR1_PLS_SHIFT) /* 101: */
-#  define PWR_CR1_PLS_2V85        (6 << PWR_CR1_PLS_SHIFT) /* 110: */
-#  define PWR_CR1_PLS_EXT         (7 << PWR_CR1_PLS_SHIFT) /* 111: */
-#define PWR_CR1_DBP               (1 << 8)   /* Bit 8: Disable backup domain write protection */
-#define PWR_CR1_FLPS              (1 << 9)   /* Bit 9: */
-                                             /* Bits 10-13: Reserved */
-#define PWR_CR1_SVOS_SHIFT        (14)       /* Bits 14-15: */
-#define PWR_CR1_SVOS_MASK         (3 << PWR_CR1_SVOS_SHIFT)
-                                                            /* 00: Reserved */
-#  define PWR_CR1_SVOS_S5         (1 << PWR_CR1_SVOS_SHIFT) /* 01:  */
-#  define PWR_CR1_SVOS_S4         (2 << PWR_CR1_SVOS_SHIFT) /* 10: */
-#  define PWR_CR1_SVOS_S3         (3 << PWR_CR1_SVOS_SHIFT) /* 11: */
-#define PWR_CR1_AVDEN             (1 << 16)  /* Bit 16: */
-#define PWR_CR1_ALS_SHIFT         (17)       /* Bits 17-18: Analog voltage detector level selection */
-#define PWR_CR1_ALS_MASK          (3 << PWR_CR1_ALS_SHIFT)
-#  define PWR_CR1_ALS_1V7         (0 << PWR_CR1_ALS_SHIFT) /* 00: */
-#  define PWR_CR1_ALS_2V1         (1 << PWR_CR1_ALS_SHIFT) /* 01 */
-#  define PWR_CR1_ALS_2V5         (2 << PWR_CR1_ALS_SHIFT) /* 10: */
-#  define PWR_CR1_ALS_2V8         (3 << PWR_CR1_ALS_SHIFT) /* 11: */
-                                             /* Bits 19-31: Reserved */
+#define PWR_CR1_LPDS                (1 << 0)    /* Bit 0: Low-power Deepsleep with SVOS3 */
+                                                /* Bits 1-3: Reserved */
+#define PWR_CR1_PVDE                (1 << 4)    /* Bit 4: Programmable voltage detector enable */
+
+
+#define PWR_CR1_PLS_SHIFT           (5)        /* Bits 5-7: Programmable voltage detector level */
+#define PWR_CR1_PLS_MASK            (7 << PWR_CR1_PLS_SHIFT)
+#  define PWR_CR1_PLS_1V95          (0 << PWR_CR1_PLS_SHIFT) /* 000: */
+#  define PWR_CR1_PLS_2V1           (1 << PWR_CR1_PLS_SHIFT) /* 001: */
+#  define PWR_CR1_PLS_2V25          (2 << PWR_CR1_PLS_SHIFT) /* 010: */
+#  define PWR_CR1_PLS_2V4           (3 << PWR_CR1_PLS_SHIFT) /* 011: */
+#  define PWR_CR1_PLS_2V55          (4 << PWR_CR1_PLS_SHIFT) /* 100: */
+#  define PWR_CR1_PLS_2V7           (5 << PWR_CR1_PLS_SHIFT) /* 101: */
+#  define PWR_CR1_PLS_2V85          (6 << PWR_CR1_PLS_SHIFT) /* 110: */
+#  define PWR_CR1_PLS_EXT           (7 << PWR_CR1_PLS_SHIFT) /* 111: */
+#define PWR_CR1_DBP                 (1 << 8)   /* Bit 8: Disable backup domain write protection */
+#define PWR_CR1_FLPS                (1 << 9)   /* Bit 9: */
+                                               /* Bits 10-13: Reserved */
+#define PWR_CR1_SVOS_SHIFT          (14)       /* Bits 14-15: */
+#define PWR_CR1_SVOS_MASK           (3 << PWR_CR1_SVOS_SHIFT)
+                                                              /* 00: Reserved */
+#  define PWR_CR1_SVOS_S5           (1 << PWR_CR1_SVOS_SHIFT) /* 01:  */
+#  define PWR_CR1_SVOS_S4           (2 << PWR_CR1_SVOS_SHIFT) /* 10: */
+#  define PWR_CR1_SVOS_S3           (3 << PWR_CR1_SVOS_SHIFT) /* 11: */
+#define PWR_CR1_AVDEN               (1 << 16)  /* Bit 16: */
+#define PWR_CR1_ALS_SHIFT           (17)       /* Bits 17-18: Analog voltage detector level selection */
+#define PWR_CR1_ALS_MASK            (3 << PWR_CR1_ALS_SHIFT)
+#  define PWR_CR1_ALS_1V7           (0 << PWR_CR1_ALS_SHIFT) /* 00: */
+#  define PWR_CR1_ALS_2V1           (1 << PWR_CR1_ALS_SHIFT) /* 01 */
+#  define PWR_CR1_ALS_2V5           (2 << PWR_CR1_ALS_SHIFT) /* 10: */
+#  define PWR_CR1_ALS_2V8           (3 << PWR_CR1_ALS_SHIFT) /* 11: */
+                                              /* Bits 19-31: Reserved */
 
 /* Power control/status register 1 (CRS1) */
 
 /* Power control register 2 (CR2) */
 
-#define PWR_CR2_BREN              (1 << 0)   /* Bit 0: Backup regulator enable */
-                                             /* Bits 1-3: Reserved */
-#define PWR_CR2_MONEN             (1 << 4)   /* Bit 4: VBAT and temperature monitoring enable */
-                                             /* Bits 5-15: Reserved */
-#define PWR_CR2_BRRDY             (1 << 16)  /* Bit 16: Backup regulator ready */
-                                             /* Bits 17-19: Reserved */
-#define PWR_CR2_VBATL             (1 << 20)  /* Bit 20: VBAT level monitoring versus low threshold */
-#define PWR_CR2_VBATH             (1 << 21)  /* Bit 21: VBAT level monitoring versus high threshold */
-#define PWR_CR2_TEMPL             (1 << 22)  /* Bit 22: Temperature level monitoring versus low threshold */
-#define PWR_CR2_TEMPH             (1 << 23)  /* Bit 23: Temperature level monitoring versus high threshold */
-                                             /* Bits 24-31: Reserved */
+#define PWR_CR2_BREN                (1 << 0)   /* Bit 0: Backup regulator enable */
+                                               /* Bits 1-3: Reserved */
+#define PWR_CR2_MONEN               (1 << 4)   /* Bit 4: VBAT and temperature monitoring enable */
+                                               /* Bits 5-15: Reserved */
+#define PWR_CR2_BRRDY               (1 << 16)  /* Bit 16: Backup regulator ready */
+                                               /* Bits 17-19: Reserved */
+#define PWR_CR2_VBATL               (1 << 20)  /* Bit 20: VBAT level monitoring versus low threshold */
+#define PWR_CR2_VBATH               (1 << 21)  /* Bit 21: VBAT level monitoring versus high threshold */
+#define PWR_CR2_TEMPL               (1 << 22)  /* Bit 22: Temperature level monitoring versus low threshold */
+#define PWR_CR2_TEMPH               (1 << 23)  /* Bit 23: Temperature level monitoring versus high threshold */
+                                               /* Bits 24-31: Reserved */
 
 /* Power control register 3 (CR3) */
 
-#define STM32_PWR_CR3_BYPASS       (1 << 0)  /* Bit 0: Power management unit bypass */
-#define STM32_PWR_CR3_LDOEN        (1 << 1)  /* Bit 1: Low drop-out regulator enable */
-#define STM32_PWR_CR3_LDOESCUEN    (1 << 2)  /* Bit 2: Supply configuration update enable */
-                                             /* Bits 3-7: Reserved */
-#define STM32_PWR_CR3_VBE          (1 << 8)  /* Bit 8: VBAT charging enable */
-#define STM32_PWR_CR3_VBRS         (1 << 9)  /* Bit 9: VBAT charging resistor selection */
-                                             /* Bits 10-23: Reserved */
-#define STM32_PWR_CR3_USB33DEN     (1 << 24) /* Bit 24: VDD33USB voltage level detector enable */
-#define STM32_PWR_CR3_USBREGEN     (1 << 25) /* Bit 25: USB regulator enable */
-#define STM32_PWR_CR3_USB33RDY     (1 << 26) /* Bit 26: USB supply ready */
+#define STM32_PWR_CR3_BYPASS        (1 << 0)  /* Bit 0: Power management unit bypass */
+#define STM32_PWR_CR3_LDOEN         (1 << 1)  /* Bit 1: Low drop-out regulator enable */
+#define STM32_PWR_CR3_LDOESCUEN     (1 << 2)  /* Bit 2: Supply configuration update enable */
+                                              /* Bits 3-7: Reserved */
+#define STM32_PWR_CR3_VBE           (1 << 8)  /* Bit 8: VBAT charging enable */
+#define STM32_PWR_CR3_VBRS          (1 << 9)  /* Bit 9: VBAT charging resistor selection */
+                                              /* Bits 10-23: Reserved */
+#define STM32_PWR_CR3_USB33DEN      (1 << 24) /* Bit 24: VDD33USB voltage level detector enable */
+#define STM32_PWR_CR3_USBREGEN      (1 << 25) /* Bit 25: USB regulator enable */
+#define STM32_PWR_CR3_USB33RDY      (1 << 26) /* Bit 26: USB supply ready */
 
 /* Power CPU control register (CPUCR) */
 
-#define STM32_PWR_CPUCR_PDDS_D1    (1 << 0)  /* Bit 0: D1 domain Power Down Deepsleep selection */
-#define STM32_PWR_CPUCR_PDDS_D2    (1 << 1)  /* Bit 1: D2 domain Power Down Deepsleep */
-#define STM32_PWR_CPUCR_PDDS_D3    (1 << 2)  /* Bit 2: System D3 domain Power Down Deepsleep */
-                                             /* Bits 3-4: Reserved */
-#define STM32_PWR_CPUCR_STOPF      (1 << 5)  /* Bit 5: STOP flag */
-#define STM32_PWR_CPUCR_SBF        (1 << 6)  /* Bit 6: System Standby flag */
-#define STM32_PWR_CPUCR_SBF_D1     (1 << 7)  /* Bit 7: D1 domain DStandby flag */
-#define STM32_PWR_CPUCR_SBF_D2     (1 << 8)  /* Bit 8: D2 domain DStandby flag */
-#define STM32_PWR_CPUCR_CSSF       (1 << 9)  /* Bit 9: Clear Standby and Stop flags (always read as 0) */
-                                             /* Bit 10: Reserved */
-#define STM32_PWR_CPUCR_RUN_D3     (1 << 11) /* Bit 11: Keep system D3 domain in Run mode regardless of the CPU subsystem modes */
-                                             /* Bits 12-31: Reserved */
+#define STM32_PWR_CPUCR_PDDS_D1     (1 << 0)  /* Bit 0: D1 domain Power Down Deepsleep selection */
+#define STM32_PWR_CPUCR_PDDS_D2     (1 << 1)  /* Bit 1: D2 domain Power Down Deepsleep */
+#define STM32_PWR_CPUCR_PDDS_D3     (1 << 2)  /* Bit 2: System D3 domain Power Down Deepsleep */
+                                              /* Bits 3-4: Reserved */
+#define STM32_PWR_CPUCR_STOPF       (1 << 5)  /* Bit 5: STOP flag */
+#define STM32_PWR_CPUCR_SBF         (1 << 6)  /* Bit 6: System Standby flag */
+#define STM32_PWR_CPUCR_SBF_D1      (1 << 7)  /* Bit 7: D1 domain DStandby flag */
+#define STM32_PWR_CPUCR_SBF_D2      (1 << 8)  /* Bit 8: D2 domain DStandby flag */
+#define STM32_PWR_CPUCR_CSSF        (1 << 9)  /* Bit 9: Clear Standby and Stop flags (always read as 0) */
+                                              /* Bit 10: Reserved */
+#define STM32_PWR_CPUCR_RUN_D3      (1 << 11) /* Bit 11: Keep system D3 domain in Run mode regardless of the CPU subsystem modes */
+                                              /* Bits 12-31: Reserved */
 
 /* Power D3 domain control register (D3CR) */
 
-                                             /* Bits 0-12: Reserved */
-#define STM32_PWR_D3CR_VOSRDY      (1 << 13) /* Bit 13:  */
-#define STM32_PWR_D3CR_VOS_SHIFT   (14)      /* Bits 14-15: Voltage scaling selection according to performance */
-#define STM32_PWR_D3CR_VOS_MASK    (3 << STM32_PWR_D3CR_VOS_SHIFT)
-#  define PWR_D3CR_VOS_SCALE_3R    (0 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 200MHz */
-#  define PWR_D3CR_VOS_SCALE_3     (1 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 200MHz */
-#  define PWR_D3CR_VOS_SCALE_2     (2 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 300MHz */
-#  define PWR_D3CR_VOS_SCALE_1     (3 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 400MHz */
-#  define PWR_D3CR_VOS_SCALE_0     (3 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 480MHz with ODN */
-                                             /* Bits 15-31: Reserved */
+                                              /* Bits 0-12: Reserved */
+#define STM32_PWR_D3CR_VOSRDY       (1 << 13) /* Bit 13:  */
+#define STM32_PWR_D3CR_VOS_SHIFT    (14)      /* Bits 14-15: Voltage scaling selection according to performance */
+#define STM32_PWR_D3CR_VOS_MASK     (3 << STM32_PWR_D3CR_VOS_SHIFT)
+#  define PWR_D3CR_VOS_SCALE_3R     (0 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 200MHz */
+#  define PWR_D3CR_VOS_SCALE_3      (1 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 200MHz */
+#  define PWR_D3CR_VOS_SCALE_2      (2 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 300MHz */
+#  define PWR_D3CR_VOS_SCALE_1      (3 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 400MHz */
+#  define PWR_D3CR_VOS_SCALE_0      (3 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 480MHz with ODN */
+                                              /* Bits 15-31: Reserved */
 
 /* Power wakeup clear register (WKUPCR) */
 
-#define STM32_PWR_WKUPC1           (1 << 0)  /* Bit 0: Clear wakeup pin flag for WKUP1 */
-#define STM32_PWR_WKUPC2           (1 << 1)  /* Bit 1: Clear wakeup pin flag for WKUP2 */
-#define STM32_PWR_WKUPC3           (1 << 2)  /* Bit 2: Clear wakeup pin flag for WKUP3 */
-#define STM32_PWR_WKUPC4           (1 << 3)  /* Bit 3: Clear wakeup pin flag for WKUP4 */
-#define STM32_PWR_WKUPC5           (1 << 4)  /* Bit 4: Clear wakeup pin flag for WKUP5 */
-#define STM32_PWR_WKUPC6           (1 << 5)  /* Bit 5: Clear wakeup pin flag for WKUP6 */
-                                             /* Bits 6-31: Reserved */
+#define STM32_PWR_WKUPC1            (1 << 0)  /* Bit 0: Clear wakeup pin flag for WKUP1 */
+#define STM32_PWR_WKUPC2            (1 << 1)  /* Bit 1: Clear wakeup pin flag for WKUP2 */
+#define STM32_PWR_WKUPC3            (1 << 2)  /* Bit 2: Clear wakeup pin flag for WKUP3 */
+#define STM32_PWR_WKUPC4            (1 << 3)  /* Bit 3: Clear wakeup pin flag for WKUP4 */
+#define STM32_PWR_WKUPC5            (1 << 4)  /* Bit 4: Clear wakeup pin flag for WKUP5 */
+#define STM32_PWR_WKUPC6            (1 << 5)  /* Bit 5: Clear wakeup pin flag for WKUP6 */
+                                              /* Bits 6-31: Reserved */
 
 /* Power wakeup flag register (WKUPFR) */
 
-#define STM32_PWR_WKUPF1           (1 << 0)  /* Bit 0: Wakeup pin flag for WKUP1 */
-#define STM32_PWR_WKUPF2           (1 << 1)  /* Bit 1: Wakeup pin flag for WKUP2 */
-#define STM32_PWR_WKUPF3           (1 << 2)  /* Bit 2: Wakeup pin flag for WKUP3 */
-#define STM32_PWR_WKUPF4           (1 << 3)  /* Bit 3: Wakeup pin flag for WKUP4 */
-#define STM32_PWR_WKUPF5           (1 << 4)  /* Bit 4: Wakeup pin flag for WKUP5 */
-#define STM32_PWR_WKUPF6           (1 << 5)  /* Bit 5: Wakeup pin flag for WKUP6 */
-                                             /* Bits 6-31: Reserved */
+#define STM32_PWR_WKUPF1            (1 << 0)  /* Bit 0: Wakeup pin flag for WKUP1 */
+#define STM32_PWR_WKUPF2            (1 << 1)  /* Bit 1: Wakeup pin flag for WKUP2 */
+#define STM32_PWR_WKUPF3            (1 << 2)  /* Bit 2: Wakeup pin flag for WKUP3 */
+#define STM32_PWR_WKUPF4            (1 << 3)  /* Bit 3: Wakeup pin flag for WKUP4 */
+#define STM32_PWR_WKUPF5            (1 << 4)  /* Bit 4: Wakeup pin flag for WKUP5 */
+#define STM32_PWR_WKUPF6            (1 << 5)  /* Bit 5: Wakeup pin flag for WKUP6 */
+                                              /* Bits 6-31: Reserved */
 
 /* Power wakeup enable and polarity register (WKUPEPR) */
 
-#define STM32_PWR_WKUPEN1          (1 << 0)  /* Bit 0: Enable wakeup pin WKUP1 */
-#define STM32_PWR_WKUPEN2          (1 << 1)  /* Bit 1: Enable wakeup pin WKUP2 */
-#define STM32_PWR_WKUPEN3          (1 << 2)  /* Bit 2: Enable wakeup pin WKUP3 */
-#define STM32_PWR_WKUPEN4          (1 << 3)  /* Bit 3: Enable wakeup pin WKUP4 */
-#define STM32_PWR_WKUPEN5          (1 << 4)  /* Bit 4: Enable wakeup pin WKUP5 */
-#define STM32_PWR_WKUPEN6          (1 << 5)  /* Bit 5: Enable wakeup pin WKUP6 */
-                                             /* Bits 6-7: Reserved */
-#define STM32_PWR_WKUPP1           (1 << 8)  /* Bit 8: Wakeup pin polarity for WKUP1 */
-#define STM32_PWR_WKUPP2           (1 << 9)  /* Bit 9: Wakeup pin polarity for WKUP2 */
-#define STM32_PWR_WKUPP3           (1 << 10) /* Bit 10: Wakeup pin polarity for WKUP3 */
-#define STM32_PWR_WKUPP4           (1 << 11) /* Bit 11: Wakeup pin polarity for WKUP4 */
-#define STM32_PWR_WKUPP5           (1 << 12) /* Bit 12: Wakeup pin polarity for WKUP5 */
-#define STM32_PWR_WKUPP6           (1 << 13) /* Bit 13: Wakeup pin polarity for WKUP6 */
-                                             /* Bits 14-15: Reserved */
-#define STM32_PWR_WKUPPUPD1_SHIFT  (16)      /* Bits 16-17: Wakeup pin pull config for WKUP1 */
-#define STM32_PWR_WKUPPUPD2_SHIFT  (18)      /* Bits 18-19: Wakeup pin pull config for WKUP2 */
-#define STM32_PWR_WKUPPUPD3_SHIFT  (20)      /* Bits 20-21: Wakeup pin pull config for WKUP3 */
-#define STM32_PWR_WKUPPUPD4_SHIFT  (22)      /* Bits 22-23: Wakeup pin pull config for WKUP4 */
-#define STM32_PWR_WKUPPUPD5_SHIFT  (24)      /* Bits 24-25: Wakeup pin pull config for WKUP5 */
-#define STM32_PWR_WKUPPUPD6_SHIFT  (26)      /* Bits 26-27: Wakeup pin pull config for WKUP6 */
+#define STM32_PWR_WKUPEN(n)         (1 << (n))
+#define STM32_PWR_WKUPEN1           (1 << 0)  /* Bit 0: Enable wakeup pin WKUP1 */
+#define STM32_PWR_WKUPEN2           (1 << 1)  /* Bit 1: Enable wakeup pin WKUP2 */
+#define STM32_PWR_WKUPEN3           (1 << 2)  /* Bit 2: Enable wakeup pin WKUP3 */
+#define STM32_PWR_WKUPEN4           (1 << 3)  /* Bit 3: Enable wakeup pin WKUP4 */
+#define STM32_PWR_WKUPEN5           (1 << 4)  /* Bit 4: Enable wakeup pin WKUP5 */
+#define STM32_PWR_WKUPEN6           (1 << 5)  /* Bit 5: Enable wakeup pin WKUP6 */
+                                              /* Bits 6-7: Reserved */
+#define STM32_PWR_WKUPP(n)          (1 << (n + 8))
+#define STM32_PWR_WKUPP1            (1 << 8)  /* Bit 8: Wakeup pin polarity for WKUP1 */
+#define STM32_PWR_WKUPP2            (1 << 9)  /* Bit 9: Wakeup pin polarity for WKUP2 */
+#define STM32_PWR_WKUPP3            (1 << 10) /* Bit 10: Wakeup pin polarity for WKUP3 */
+#define STM32_PWR_WKUPP4            (1 << 11) /* Bit 11: Wakeup pin polarity for WKUP4 */
+#define STM32_PWR_WKUPP5            (1 << 12) /* Bit 12: Wakeup pin polarity for WKUP5 */
+#define STM32_PWR_WKUPP6            (1 << 13) /* Bit 13: Wakeup pin polarity for WKUP6 */
+                                              /* Bits 14-15: Reserved */
+#define STM32_PWR_WKUPPUPD_SHIFT(n) (n * 2 + 16)
+#define STM32_PWR_WKUPPUPD1_SHIFT   (16)      /* Bits 16-17: Wakeup pin pull config for WKUP1 */
+#define STM32_PWR_WKUPPUPD2_SHIFT   (18)      /* Bits 18-19: Wakeup pin pull config for WKUP2 */
+#define STM32_PWR_WKUPPUPD3_SHIFT   (20)      /* Bits 20-21: Wakeup pin pull config for WKUP3 */
+#define STM32_PWR_WKUPPUPD4_SHIFT   (22)      /* Bits 22-23: Wakeup pin pull config for WKUP4 */
+#define STM32_PWR_WKUPPUPD5_SHIFT   (24)      /* Bits 24-25: Wakeup pin pull config for WKUP5 */
+#define STM32_PWR_WKUPPUPD6_SHIFT   (26)      /* Bits 26-27: Wakeup pin pull config for WKUP6 */
 # define STM32_PWR_WKUPPUPD_NONE    (0)      /* No pull-up */
 # define STM32_PWR_WKUPPUPD_PULLUP  (1)      /* Pull-up enabled */
 # define STM32_PWR_WKUPPUPD_PULLDN  (2)      /* Pull-down enabled */
                                              /* 3 is reserved */
+# define STM32_PWR_WKUPPUPD_MASK    (3)
                                              /* Bits 28-31: Reserved */
 
 #endif /* __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7X3XX_PWR_H */
diff --git a/arch/arm/src/stm32h7/stm32_pwr.c b/arch/arm/src/stm32h7/stm32_pwr.c
index 71c041c..a676227 100644
--- a/arch/arm/src/stm32h7/stm32_pwr.c
+++ b/arch/arm/src/stm32h7/stm32_pwr.c
@@ -50,6 +50,7 @@
 #include "barriers.h"
 #include "up_arch.h"
 #include "stm32_pwr.h"
+#include "stm32_gpio.h"
 
 #if defined(CONFIG_STM32H7_PWR)
 
@@ -274,7 +275,7 @@ void stm32_pwr_disablepvd(void)
  *   the Backup Regulator Ready flag (BRR) is set to indicate that the data written
  *   into the RAM will be maintained in the Standby and VBAT modes.
  *
- *   This function need to be called after stm32_pwr_enablebkp(true) has ben called.
+ *   This function needs to be called after stm32_pwr_enablebkp(true) has been called.
  *
  * Input Parameters:
  *   region - state to set it to
@@ -316,4 +317,70 @@ void stm32_pwr_enablebreg(bool region)
 
   leave_critical_section(flags);
 }
+
+/************************************************************************************
+ * Name: stm32_pwr_configurewkup
+ *
+ * Description:
+ *   Configures the external wakeup (WKUP) signals for wakeup from standby mode.
+ *   Sets rising/falling edge sensitivity and pull state.
+ *
+ *
+ * Input Parameters:
+ *   pin    - WKUP pin number (0-5) to work on
+ *   en     - Enables the specified WKUP pin if true
+ *   rising - If true, wakeup is triggered on rising edge, otherwise,
+ *            it is triggered on the falling edge.
+ *   pull   - Specifies the WKUP pin pull resistor configuration
+ *            (GPIO_FLOAT, GPIO_PULLUP, or GPIO_PULLDOWN)
+ *
+ * Returned Value:
+ *   None
+ *
+ ************************************************************************************/
+
+void stm32_pwr_configurewkup(uint32_t pin, bool en, bool rising, uint32_t pull)
+{
+  irqstate_t flags;
+  uint32_t regval;
+
+  DEBUGASSERT(pin < 6);
+
+  flags = enter_critical_section();
+
+  regval      = stm32_pwr_getreg(STM32_PWR_WKUPEPR_OFFSET);
+
+  if (en)
+    {
+      regval     |= STM32_PWR_WKUPEN(pin);
+    }
+  else
+    {
+      regval     &= ~STM32_PWR_WKUPEN(pin);
+    }
+
+  if (rising)
+    {
+      regval     &= ~STM32_PWR_WKUPP(pin);
+    }
+  else
+    {
+      regval     |= STM32_PWR_WKUPP(pin);
+    }
+  /* Set to the no pull-up state by default*/
+  regval &= ~ (STM32_PWR_WKUPPUPD_MASK << STM32_PWR_WKUPPUPD_SHIFT(pin));
+
+  if (pull == GPIO_PULLUP)
+    {
+      regval     |= STM32_PWR_WKUPPUPD_PULLUP << STM32_PWR_WKUPPUPD_SHIFT(pin);
+    }
+  else if (pull == GPIO_PULLDOWN)
+    {
+      regval     |= STM32_PWR_WKUPPUPD_PULLDN << STM32_PWR_WKUPPUPD_SHIFT(pin);
+    }
+
+  stm32_pwr_putreg(STM32_PWR_WKUPEPR_OFFSET, regval);
+
+  leave_critical_section(flags);
+}
 #endif /* CONFIG_STM32_PWR */
diff --git a/arch/arm/src/stm32h7/stm32_pwr.h b/arch/arm/src/stm32h7/stm32_pwr.h
index a9b529c..761c158 100644
--- a/arch/arm/src/stm32h7/stm32_pwr.h
+++ b/arch/arm/src/stm32h7/stm32_pwr.h
@@ -125,6 +125,29 @@ void stm32_pwr_enablebkp(bool writable);
 
 void stm32_pwr_enablebreg(bool region);
 
+/************************************************************************************
+ * Name: stm32_pwr_configurewkup
+ *
+ * Description:
+ *   Configures the external wakeup (WKUP) signals for wakeup from standby mode.
+ *   Sets rising/falling edge sensitivity and pull state.
+ *
+ *
+ * Input Parameters:
+ *   pin    - WKUP pin number (0-5) to work on
+ *   en     - Enables the specified WKUP pin if true
+ *   rising - If true, wakeup is triggered on rising edge, otherwise,
+ *            it is triggered on the falling edge.
+ *   pull   - Specifies the WKUP pin pull resistor configuration
+ *            (GPIO_FLOAT, GPIO_PULLUP, or GPIO_PULLDOWN)
+ *
+ * Returned Value:
+ *   None
+ *
+ ************************************************************************************/
+
+void stm32_pwr_configurewkup(uint32_t pin, bool en, bool rising, uint32_t pull);
+
 #undef EXTERN
 #if defined(__cplusplus)
 }


[incubator-nuttx] 06/13: Handle case where only ADC1 or ADC2 is enabled.

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit e405e5977364162ced47e6ed754359e9b083f95d
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Mon Feb 10 11:39:33 2020 -0600

    Handle case where only ADC1 or ADC2 is enabled.
---
 arch/arm/src/stm32h7/stm32_adc.c | 6 ++++--
 1 file changed, 4 insertions(+), 2 deletions(-)

diff --git a/arch/arm/src/stm32h7/stm32_adc.c b/arch/arm/src/stm32h7/stm32_adc.c
index 854034f..c3e6975 100644
--- a/arch/arm/src/stm32h7/stm32_adc.c
+++ b/arch/arm/src/stm32h7/stm32_adc.c
@@ -1329,13 +1329,15 @@ static int adc_setup(FAR struct adc_dev_s *dev)
 
   /* Make sure that the ADC device is in the powered up, reset state.
    * Since reset is shared between ADC1 and ADC2, don't reset one if the
-   * other has already been reset.
+   * other has already been reset. (We only need to worry about this if both
+   * ADC1 and ADC2 are enabled.)
    */
-
+#if defined(CONFIG_STM32H7_ADC1) && defined(CONFIG_STM32H7_ADC2)
   if ((dev == &g_adcdev1 &&
       !((FAR struct stm32_dev_s *)g_adcdev2.ad_priv)->initialized) ||
      (dev == &g_adcdev2 &&
       !((FAR struct stm32_dev_s *)g_adcdev1.ad_priv)->initialized))
+#endif
   {
      adc_reset(dev);
   }


[incubator-nuttx] 05/13: Added basic support for IWDG and WWDG to STM32H7

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit a7c5016a4124cad0d367982572a52961a776f8de
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Wed Feb 5 14:12:59 2020 -0600

    Added basic support for IWDG and WWDG to STM32H7
---
 arch/arm/src/stm32h7/Kconfig              |  10 +
 arch/arm/src/stm32h7/Make.defs            |   8 +
 arch/arm/src/stm32h7/hardware/stm32_wdg.h | 158 ++++++
 arch/arm/src/stm32h7/stm32_iwdg.c         | 699 ++++++++++++++++++++++++++
 arch/arm/src/stm32h7/stm32_wdg.h          | 119 +++++
 arch/arm/src/stm32h7/stm32_wwdg.c         | 798 ++++++++++++++++++++++++++++++
 6 files changed, 1792 insertions(+)

diff --git a/arch/arm/src/stm32h7/Kconfig b/arch/arm/src/stm32h7/Kconfig
index 3c07db3..2b552ce 100644
--- a/arch/arm/src/stm32h7/Kconfig
+++ b/arch/arm/src/stm32h7/Kconfig
@@ -341,6 +341,16 @@ config STM32H7_SDMMC2
 	select ARCH_HAVE_SDIO_PREFLIGHT
 	select SDIO_BLOCKSETUP
 
+config STM32H7_IWDG
+	bool "IWDG"
+	default n
+	select WATCHDOG
+
+config STM32H7_WWDG
+	bool "WWDG"
+	default n
+	select WATCHDOG
+
 menu "STM32H7 I2C Selection"
 
 config STM32H7_I2C1
diff --git a/arch/arm/src/stm32h7/Make.defs b/arch/arm/src/stm32h7/Make.defs
index a8e37aa..4a63041 100644
--- a/arch/arm/src/stm32h7/Make.defs
+++ b/arch/arm/src/stm32h7/Make.defs
@@ -217,3 +217,11 @@ ifneq ($(CONFIG_ARCH_CUSTOM_PMINIT),y)
 CHIP_CSRCS += stm32_pminitialize.c
 endif
 endif
+
+ifeq ($(CONFIG_STM32H7_IWDG),y)
+CHIP_CSRCS += stm32_iwdg.c
+endif
+
+ifeq ($(CONFIG_STM32H7_WWDG),y)
+CHIP_CSRCS += stm32_wwdg.c
+endif
diff --git a/arch/arm/src/stm32h7/hardware/stm32_wdg.h b/arch/arm/src/stm32h7/hardware/stm32_wdg.h
new file mode 100644
index 0000000..7004b60
--- /dev/null
+++ b/arch/arm/src/stm32h7/hardware/stm32_wdg.h
@@ -0,0 +1,158 @@
+/************************************************************************************
+ * arch/arm/src/stm32h7/hardware/stm32_wdg.h
+ *
+ *   Copyright (C) 2009, 2011-2013 Gregory Nutt. All rights reserved.
+ *   Author: Gregory Nutt <gn...@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_HARDWARE_STM32H7_WDG_H
+#define __ARCH_ARM_SRC_STM32_HARDWARE_STM32H7_WDG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Register Offsets *****************************************************************/
+
+#define STM32_IWDG_KR_OFFSET     0x0000  /* Key register (32-bit) */
+#define STM32_IWDG_PR_OFFSET     0x0004  /* Prescaler register (32-bit) */
+#define STM32_IWDG_RLR_OFFSET    0x0008  /* Reload register (32-bit) */
+#define STM32_IWDG_SR_OFFSET     0x000c  /* Status register (32-bit) */
+#define STM32_IWDG_WINR_OFFSET   0x000c  /* Window register (32-bit) */
+
+#define STM32_WWDG_CR_OFFSET     0x0000  /* Control Register (32-bit) */
+#define STM32_WWDG_CFR_OFFSET    0x0004  /* Configuration register (32-bit) */
+#define STM32_WWDG_SR_OFFSET     0x0008  /* Status register (32-bit) */
+
+/* Register Addresses ***************************************************************/
+
+#define STM32_IWDG_KR            (STM32_IWDG1_BASE+STM32_IWDG_KR_OFFSET)
+#define STM32_IWDG_PR            (STM32_IWDG1_BASE+STM32_IWDG_PR_OFFSET)
+#define STM32_IWDG_RLR           (STM32_IWDG1_BASE+STM32_IWDG_RLR_OFFSET)
+#define STM32_IWDG_SR            (STM32_IWDG1_BASE+STM32_IWDG_SR_OFFSET)
+#define STM32_IWDG_WINR          (STM32_IWDG1_BASE+STM32_IWDG_WINR_OFFSET)
+
+#define STM32_WWDG_CR            (STM32_WWDG1_BASE+STM32_WWDG_CR_OFFSET)
+#define STM32_WWDG_CFR           (STM32_WWDG1_BASE+STM32_WWDG_CFR_OFFSET)
+#define STM32_WWDG_SR            (STM32_WWDG1_BASE+STM32_WWDG_SR_OFFSET)
+
+/* Register Bitfield Definitions ****************************************************/
+
+/* Key register (32-bit) */
+
+#define IWDG_KR_KEY_SHIFT        (0)       /* Bits 15-0: Key value (write only, read 0000h) */
+#define IWDG_KR_KEY_MASK         (0xffff << IWDG_KR_KEY_SHIFT)
+
+#define IWDG_KR_KEY_ENABLE       (0x5555)  /* Enable register access */
+#define IWDG_KR_KEY_DISABLE      (0x0000)  /* Disable register access */
+#define IWDG_KR_KEY_RELOAD       (0xaaaa)  /* Reload the counter */
+#define IWDG_KR_KEY_START        (0xcccc)  /* Start the watchdog */
+
+/* Prescaler register (32-bit) */
+
+#define IWDG_PR_SHIFT            (0)       /* Bits 2-0: Prescaler divider */
+#define IWDG_PR_MASK             (7 << IWDG_PR_SHIFT)
+#  define IWDG_PR_DIV4           (0 << IWDG_PR_SHIFT) /* 000: divider /4 */
+#  define IWDG_PR_DIV8           (1 << IWDG_PR_SHIFT) /* 001: divider /8 */
+#  define IWDG_PR_DIV16          (2 << IWDG_PR_SHIFT) /* 010: divider /16 */
+#  define IWDG_PR_DIV32          (3 << IWDG_PR_SHIFT) /* 011: divider /32 */
+#  define IWDG_PR_DIV64          (4 << IWDG_PR_SHIFT) /* 100: divider /64 */
+#  define IWDG_PR_DIV128         (5 << IWDG_PR_SHIFT) /* 101: divider /128 */
+#  define IWDG_PR_DIV256         (6 << IWDG_PR_SHIFT) /* 11x: divider /256 */
+
+/* Reload register (32-bit) */
+
+#define IWDG_RLR_RL_SHIFT        (0)       /* Bits11:0 RL[11:0]: Watchdog counter reload value */
+#define IWDG_RLR_RL_MASK         (0x0fff << IWDG_RLR_RL_SHIFT)
+
+#define IWDG_RLR_MAX             (0xfff)
+
+/* Status register (32-bit) */
+
+#define IWDG_SR_PVU              (1 << 0)  /* Bit 0: Watchdog prescaler value update */
+#define IWDG_SR_RVU              (1 << 1)  /* Bit 1: Watchdog counter reload value update */
+
+#if defined(CONFIG_STM32_STM32F30XX)
+#  define IWDG_SR_WVU            (1 << 2)  /* Bit 2:  */
+#endif
+
+/* Window register (32-bit) */
+
+#if defined(CONFIG_STM32_STM32F30XX)
+#  define IWDG_WINR_SHIFT        (0)
+#  define IWDG_WINR_MASK         (0x0fff << IWDG_WINR_SHIFT)
+#endif
+
+/* Control Register (32-bit) */
+
+#define WWDG_CR_T_SHIFT          (0)       /* Bits 6:0 T[6:0]: 7-bit counter (MSB to LSB) */
+#define WWDG_CR_T_MASK           (0x7f << WWDG_CR_T_SHIFT)
+#  define WWDG_CR_T_MAX          (0x3f << WWDG_CR_T_SHIFT)
+#  define WWDG_CR_T_RESET        (0x40 << WWDG_CR_T_SHIFT)
+#define WWDG_CR_WDGA             (1 << 7)  /* Bit 7: Activation bit */
+
+/* Configuration register (32-bit) */
+
+#define WWDG_CFR_W_SHIFT         (0)       /* Bits 6:0 W[6:0] 7-bit window value */
+#define WWDG_CFR_W_MASK          (0x7f << WWDG_CFR_W_SHIFT)
+#define WWDG_CFR_WDGTB_SHIFT     (7)       /* Bits 8:7 [1:0]: Timer Base */
+#define WWDG_CFR_WDGTB_MASK      (3 << WWDG_CFR_WDGTB_SHIFT)
+#  define WWDG_CFR_PCLK1         (0 << WWDG_CFR_WDGTB_SHIFT) /* 00: CK Counter Clock (PCLK1 div 4096) div 1 */
+#  define WWDG_CFR_PCLK1d2       (1 << WWDG_CFR_WDGTB_SHIFT) /* 01: CK Counter Clock (PCLK1 div 4096) div 2 */
+#  define WWDG_CFR_PCLK1d4       (2 << WWDG_CFR_WDGTB_SHIFT) /* 10: CK Counter Clock (PCLK1 div 4096) div 4 */
+#  define WWDG_CFR_PCLK1d8       (3 << WWDG_CFR_WDGTB_SHIFT) /* 11: CK Counter Clock (PCLK1 div 4096) div 8 */
+#define WWDG_CFR_EWI             (1 << 9)  /* Bit 9: Early Wakeup Interrupt */
+
+/* Status register (32-bit) */
+
+#define WWDG_SR_EWIF             (1 << 0)  /* Bit 0: Early Wakeup Interrupt Flag */
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_STM32_HARDWARE_STM32H7_WDG_H */
diff --git a/arch/arm/src/stm32h7/stm32_iwdg.c b/arch/arm/src/stm32h7/stm32_iwdg.c
new file mode 100644
index 0000000..184592a
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_iwdg.c
@@ -0,0 +1,699 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_iwdg.c
+ *
+ *   Copyright (C) 2012, 2016 Gregory Nutt. All rights reserved.
+ *   Author: Gregory Nutt <gn...@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/clock.h>
+#include <nuttx/timers/watchdog.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "stm32_rcc.h"
+#include "stm32_wdg.h"
+
+#if defined(CONFIG_WATCHDOG) && defined(CONFIG_STM32H7_IWDG)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Clocking *****************************************************************/
+/* The minimum frequency of the IWDG clock is:
+ *
+ *  Fmin = Flsi / 256
+ *
+ * So the maximum delay (in milliseconds) is then:
+ *
+ *   1000 * IWDG_RLR_MAX / Fmin
+ *
+ * For example, if Flsi = 30Khz (the nominal, uncalibrated value), then the
+ * maximum delay is:
+ *
+ *   Fmin = 117.1875
+ *   1000 * 4095 / Fmin = 34,944 MSec
+ */
+
+#define IWDG_FMIN       (STM32_LSI_FREQUENCY / 256)
+#define IWDG_MAXTIMEOUT (1000 * IWDG_RLR_MAX / IWDG_FMIN)
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_STM32H7_IWDG_DEFTIMOUT
+#  define CONFIG_STM32H7_IWDG_DEFTIMOUT IWDG_MAXTIMEOUT
+#endif
+
+#ifndef CONFIG_DEBUG_WATCHDOG_INFO
+#  undef CONFIG_STM32H7_IWDG_REGDEBUG
+#endif
+
+/* REVISIT:  It appears that you can only setup the prescaler and reload
+ * registers once.  After that, the SR register's PVU and RVU bits never go
+ * to zero.  So we defer setting up these registers until the watchdog
+ * is started, then refuse any further attempts to change timeout.
+ */
+
+#define CONFIG_STM32H7_IWDG_ONETIMESETUP 1
+
+/* REVISIT:  Another possibility is that we CAN change the prescaler and
+ * reload values after starting the timer.  This option is untested but the
+ * implementation place conditioned on the following:
+ */
+
+#undef CONFIG_STM32H7_IWDG_DEFERREDSETUP
+
+/* But you can only try one at a time */
+
+#if defined(CONFIG_STM32H7_IWDG_ONETIMESETUP) && defined(CONFIG_STM32H7_IWDG_DEFERREDSETUP)
+#  error "Both CONFIG_STM32H7_IWDG_ONETIMESETUP and CONFIG_STM32H7_IWDG_DEFERREDSETUP are defined"
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+/* This structure provides the private representation of the "lower-half"
+ * driver state structure.  This structure must be cast-compatible with the
+ * well-known watchdog_lowerhalf_s structure.
+ */
+
+struct stm32_lowerhalf_s
+{
+  FAR const struct watchdog_ops_s  *ops;  /* Lower half operations */
+  uint32_t lsifreq;   /* The calibrated frequency of the LSI oscillator */
+  uint32_t timeout;   /* The (actual) selected timeout */
+  uint32_t lastreset; /* The last reset time */
+  bool     started;   /* true: The watchdog timer has been started */
+  uint8_t  prescaler; /* Clock prescaler value */
+  uint16_t reload;    /* Timer reload value */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+/* Register operations ******************************************************/
+
+#ifdef CONFIG_STM32H7_IWDG_REGDEBUG
+static uint16_t stm32_getreg(uint32_t addr);
+static void     stm32_putreg(uint16_t val, uint32_t addr);
+#else
+# define        stm32_getreg(addr)     getreg16(addr)
+# define        stm32_putreg(val,addr) putreg16(val,addr)
+#endif
+
+static inline void stm32_setprescaler(FAR struct stm32_lowerhalf_s *priv);
+
+/* "Lower half" driver methods **********************************************/
+
+static int      stm32_start(FAR struct watchdog_lowerhalf_s *lower);
+static int      stm32_stop(FAR struct watchdog_lowerhalf_s *lower);
+static int      stm32_keepalive(FAR struct watchdog_lowerhalf_s *lower);
+static int      stm32_getstatus(FAR struct watchdog_lowerhalf_s *lower,
+                  FAR struct watchdog_status_s *status);
+static int      stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
+                  uint32_t timeout);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* "Lower half" driver methods */
+
+static const struct watchdog_ops_s g_wdgops =
+{
+  .start      = stm32_start,
+  .stop       = stm32_stop,
+  .keepalive  = stm32_keepalive,
+  .getstatus  = stm32_getstatus,
+  .settimeout = stm32_settimeout,
+  .capture    = NULL,
+  .ioctl      = NULL,
+};
+
+/* "Lower half" driver state */
+
+static struct stm32_lowerhalf_s g_wdgdev;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_getreg
+ *
+ * Description:
+ *   Get the contents of an STM32 IWDG register
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32H7_IWDG_REGDEBUG
+static uint16_t stm32_getreg(uint32_t addr)
+{
+  static uint32_t prevaddr = 0;
+  static uint32_t count = 0;
+  static uint16_t preval = 0;
+
+  /* Read the value from the register */
+
+  uint16_t val = getreg16(addr);
+
+  /* Is this the same value that we read from the same register last time?  Are
+   * we polling the register?  If so, suppress some of the output.
+   */
+
+  if (addr == prevaddr && val == preval)
+    {
+      if (count == 0xffffffff || ++count > 3)
+        {
+          if (count == 4)
+            {
+              wdinfo("...\n");
+            }
+
+          return val;
+        }
+    }
+
+  /* No this is a new address or value */
+
+  else
+    {
+      /* Did we print "..." for the previous value? */
+
+      if (count > 3)
+        {
+          /* Yes.. then show how many times the value repeated */
+
+          wdinfo("[repeats %d more times]\n", count-3);
+        }
+
+      /* Save the new address, value, and count */
+
+      prevaddr = addr;
+      preval   = val;
+      count    = 1;
+    }
+
+  /* Show the register value read */
+
+  wdinfo("%08x->%04x\n", addr, val);
+  return val;
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_putreg
+ *
+ * Description:
+ *   Set the contents of an STM32 register to a value
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32H7_IWDG_REGDEBUG
+static void stm32_putreg(uint16_t val, uint32_t addr)
+{
+  /* Show the register value being written */
+
+  wdinfo("%08x<-%04x\n", addr, val);
+
+  /* Write the value */
+
+  putreg16(val, addr);
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_setprescaler
+ *
+ * Description:
+ *   Set up the prescaler and reload values.  This seems to be something
+ *   that can only be done one time.
+ *
+ * Input Parameters:
+ *   priv   - A pointer the internal representation of the "lower-half"
+ *             driver state structure.
+ *
+ ****************************************************************************/
+
+static inline void stm32_setprescaler(FAR struct stm32_lowerhalf_s *priv)
+{
+  /* Enable write access to IWDG_PR and IWDG_RLR registers */
+
+  stm32_putreg(IWDG_KR_KEY_ENABLE, STM32_IWDG_KR);
+
+  /* Wait for the PVU and RVU bits to be reset be hardware.  These bits
+   * were set the last time that the PR register was written and may not
+   * yet be cleared.
+   *
+   * If the setup is only permitted one time, then this wait should not
+   * be necessary.
+   */
+
+#ifndef CONFIG_STM32H7_IWDG_ONETIMESETUP
+  while ((stm32_getreg(STM32_IWDG_SR) & (IWDG_SR_PVU | IWDG_SR_RVU)) != 0);
+#endif
+
+  /* Set the prescaler */
+
+  stm32_putreg((uint16_t)priv->prescaler << IWDG_PR_SHIFT, STM32_IWDG_PR);
+
+  /* Set the reload value */
+
+  stm32_putreg((uint16_t)priv->reload, STM32_IWDG_RLR);
+
+  /* Reload the counter (and disable write access) */
+
+  stm32_putreg(IWDG_KR_KEY_RELOAD, STM32_IWDG_KR);
+}
+
+/****************************************************************************
+ * Name: stm32_start
+ *
+ * Description:
+ *   Start the watchdog timer, resetting the time to the current timeout,
+ *
+ * Input Parameters:
+ *   lower - A pointer the publicly visible representation of the "lower-half"
+ *           driver state structure.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_start(FAR struct watchdog_lowerhalf_s *lower)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  irqstate_t flags;
+
+  wdinfo("Entry: started=%d\n");
+  DEBUGASSERT(priv);
+
+  /* Have we already been started? */
+
+  if (!priv->started)
+    {
+      /* REVISIT:  It appears that you can only setup the prescaler and reload
+       * registers once.  After that, the SR register's PVU and RVU bits never go
+       * to zero.  So we defer setting up these registers until the watchdog
+       * is started, then refuse any further attempts to change timeout.
+       */
+
+      /* Set up prescaler and reload value for the selected timeout before
+       * starting the watchdog timer.
+       */
+
+#if defined(CONFIG_STM32H7_IWDG_ONETIMESETUP) || defined(CONFIG_STM32H7_IWDG_DEFERREDSETUP)
+      stm32_setprescaler(priv);
+#endif
+
+      /* Enable IWDG (the LSI oscillator will be enabled by hardware).  NOTE:
+       * If the "Hardware watchdog" feature is enabled through the device option
+       * bits, the watchdog is automatically enabled at power-on.
+       */
+
+      flags           = enter_critical_section();
+      stm32_putreg(IWDG_KR_KEY_START, STM32_IWDG_KR);
+      priv->lastreset = clock_systimer();
+      priv->started   = true;
+      leave_critical_section(flags);
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_stop
+ *
+ * Description:
+ *   Stop the watchdog timer
+ *
+ * Input Parameters:
+ *   lower - A pointer the publicly visible representation of the "lower-half"
+ *           driver state structure.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_stop(FAR struct watchdog_lowerhalf_s *lower)
+{
+  /* There is no way to disable the IDWG timer once it has been started */
+
+  wdinfo("Entry\n");
+  return -ENOSYS;
+}
+
+/****************************************************************************
+ * Name: stm32_keepalive
+ *
+ * Description:
+ *   Reset the watchdog timer to the current timeout value, prevent any
+ *   imminent watchdog timeouts.  This is sometimes referred as "pinging"
+ *   the watchdog timer or "petting the dog".
+ *
+ * Input Parameters:
+ *   lower - A pointer the publicly visible representation of the "lower-half"
+ *           driver state structure.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_keepalive(FAR struct watchdog_lowerhalf_s *lower)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  irqstate_t flags;
+
+  wdinfo("Entry\n");
+
+  /* Reload the IWDG timer */
+
+  flags = enter_critical_section();
+  stm32_putreg(IWDG_KR_KEY_RELOAD, STM32_IWDG_KR);
+  priv->lastreset = clock_systimer();
+  leave_critical_section(flags);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_getstatus
+ *
+ * Description:
+ *   Get the current watchdog timer status
+ *
+ * Input Parameters:
+ *   lower  - A pointer the publicly visible representation of the "lower-half"
+ *            driver state structure.
+ *   status - The location to return the watchdog status information.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_getstatus(FAR struct watchdog_lowerhalf_s *lower,
+                           FAR struct watchdog_status_s *status)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  uint32_t ticks;
+  uint32_t elapsed;
+
+  wdinfo("Entry\n");
+  DEBUGASSERT(priv);
+
+  /* Return the status bit */
+
+  status->flags = WDFLAGS_RESET;
+  if (priv->started)
+    {
+      status->flags |= WDFLAGS_ACTIVE;
+    }
+
+  /* Return the actual timeout in milliseconds */
+
+  status->timeout = priv->timeout;
+
+  /* Get the elapsed time since the last ping */
+
+  ticks   = clock_systimer() - priv->lastreset;
+  elapsed = (int32_t)TICK2MSEC(ticks);
+
+  if (elapsed > priv->timeout)
+    {
+      elapsed = priv->timeout;
+    }
+
+  /* Return the approximate time until the watchdog timer expiration */
+
+  status->timeleft = priv->timeout - elapsed;
+
+  wdinfo("Status     :\n");
+  wdinfo("  flags    : %08x\n", status->flags);
+  wdinfo("  timeout  : %d\n", status->timeout);
+  wdinfo("  timeleft : %d\n", status->timeleft);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_settimeout
+ *
+ * Description:
+ *   Set a new timeout value (and reset the watchdog timer)
+ *
+ * Input Parameters:
+ *   lower   - A pointer the publicly visible representation of the "lower-half"
+ *             driver state structure.
+ *   timeout - The new timeout value in milliseconds.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
+                            uint32_t timeout)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  uint32_t fiwdg;
+  uint64_t reload;
+  int prescaler;
+  int shift;
+
+  wdinfo("Entry: timeout=%d\n", timeout);
+  DEBUGASSERT(priv);
+
+  /* Can this timeout be represented? */
+
+  if (timeout < 1 || timeout > IWDG_MAXTIMEOUT)
+    {
+      wderr("ERROR: Cannot represent timeout=%d > %d\n",
+            timeout, IWDG_MAXTIMEOUT);
+      return -ERANGE;
+    }
+
+  /* REVISIT:  It appears that you can only setup the prescaler and reload
+   * registers once.  After that, the SR register's PVU and RVU bits never go
+   * to zero.
+   */
+
+#ifdef CONFIG_STM32H7_IWDG_ONETIMESETUP
+  if (priv->started)
+    {
+      wdwarn("WARNING: Timer is already started\n");
+      return -EBUSY;
+    }
+#endif
+
+  /* Select the smallest prescaler that will result in a reload value that is
+   * less than the maximum.
+   */
+
+  for (prescaler = 0; ; prescaler++)
+    {
+      /* PR = 0 -> Divider = 4   = 1 << 2
+       * PR = 1 -> Divider = 8   = 1 << 3
+       * PR = 2 -> Divider = 16  = 1 << 4
+       * PR = 3 -> Divider = 32  = 1 << 5
+       * PR = 4 -> Divider = 64  = 1 << 6
+       * PR = 5 -> Divider = 128 = 1 << 7
+       * PR = 6 -> Divider = 256 = 1 << 8
+       * PR = n -> Divider       = 1 << (n+2)
+       */
+
+      shift = prescaler + 2;
+
+      /* Get the IWDG counter frequency in Hz. For a nominal 32Khz LSI clock,
+       * this is value in the range of 7500 and 125.
+       */
+
+      fiwdg = priv->lsifreq >> shift;
+
+      /* We want:
+       *  1000 * reload / Fiwdg = timeout
+       * Or:
+       *  reload = Fiwdg * timeout / 1000
+       */
+
+      reload = (uint64_t)fiwdg * (uint64_t)timeout / 1000;
+
+      /* If this reload valid is less than the maximum or we are not ready
+       * at the prescaler value, then break out of the loop to use these
+       * settings.
+       */
+
+      if (reload <= IWDG_RLR_MAX || prescaler == 6)
+        {
+          /* Note that we explicitly break out of the loop rather than using
+           * the 'for' loop termination logic because we do not want the
+           * value of prescaler to be incremented.
+           */
+
+          break;
+        }
+    }
+
+  /* Make sure that the final reload value is within range */
+
+  if (reload > IWDG_RLR_MAX)
+    {
+      reload = IWDG_RLR_MAX;
+    }
+
+  /* Get the actual timeout value in milliseconds.
+   *
+   * We have:
+   *  reload = Fiwdg * timeout / 1000
+   * So we want:
+   *  timeout = 1000 * reload / Fiwdg
+   */
+
+  priv->timeout = (1000 * (uint32_t)reload) / fiwdg;
+
+  /* Save setup values for later use */
+
+  priv->prescaler = prescaler;
+  priv->reload    = reload;
+
+  /* Write the prescaler and reload values to the IWDG registers.
+   *
+   * REVISIT:  It appears that you can only setup the prescaler and reload
+   * registers once.  After that, the SR register's PVU and RVU bits never go
+   * to zero.
+   */
+
+#ifndef CONFIG_STM32H7_IWDG_ONETIMESETUP
+  /* If CONFIG_STM32H7_IWDG_DEFERREDSETUP is selected, then perform the register
+   * configuration only if the timer has been started.
+   */
+
+#ifdef CONFIG_STM32H7_IWDG_DEFERREDSETUP
+  if (priv->started)
+#endif
+    {
+      stm32_setprescaler(priv);
+    }
+#endif
+
+  wdinfo("prescaler=%d fiwdg=%d reload=%d\n", prescaler, fiwdg, reload);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_iwdginitialize
+ *
+ * Description:
+ *   Initialize the IWDG watchdog timer.  The watchdog timer is initialized and
+ *   registers as 'devpath'.  The initial state of the watchdog timer is
+ *   disabled.
+ *
+ * Input Parameters:
+ *   devpath - The full path to the watchdog.  This should be of the form
+ *     /dev/watchdog0
+ *   lsifreq - The calibrated LSI clock frequency
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_iwdginitialize(FAR const char *devpath, uint32_t lsifreq)
+{
+  FAR struct stm32_lowerhalf_s *priv = &g_wdgdev;
+
+  wdinfo("Entry: devpath=%s lsifreq=%d\n", devpath, lsifreq);
+
+  /* NOTE we assume that clocking to the IWDG has already been provided by
+   * the RCC initialization logic.
+   */
+
+  /* Initialize the driver state structure. */
+
+  priv->ops     = &g_wdgops;
+  priv->lsifreq = lsifreq;
+  priv->started = false;
+
+  /* Make sure that the LSI oscillator is enabled.  NOTE:  The LSI oscillator
+   * is enabled here but is not disabled by this file, because this file does
+   * not know the global usage of the oscillator.  Any clock management
+   * logic (say, as part of a power management scheme) needs handle other
+   * LSI controls outside of this file.
+   */
+
+  stm32_rcc_enablelsi();
+  wdinfo("RCC CSR: %08x\n", getreg32(STM32_RCC_CSR));
+
+  /* Select an arbitrary initial timeout value.  But don't start the watchdog
+   * yet. NOTE: If the "Hardware watchdog" feature is enabled through the
+   * device option bits, the watchdog is automatically enabled at power-on.
+   */
+
+  stm32_settimeout((FAR struct watchdog_lowerhalf_s *)priv, CONFIG_STM32H7_IWDG_DEFTIMOUT);
+
+  /* Register the watchdog driver as /dev/watchdog0 */
+
+  watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv);
+
+  /* When the microcontroller enters debug mode (Cortex-M4F core halted),
+   * the IWDG counter either continues to work normally or stops, depending
+   * on DBG_IWDG_STOP configuration bit in DBG module.
+   */
+
+#if defined(CONFIG_STM32H7_JTAG_FULL_ENABLE) || \
+    defined(CONFIG_STM32H7_JTAG_NOJNTRST_ENABLE) || \
+    defined(CONFIG_STM32H7_JTAG_SW_ENABLE)
+    {
+      uint32_t cr = getreg32(STM32_DBGMCU_APB4_FZ1);
+      cr |= DBGMCU_APB4_WDGLSD1;
+      putreg32(cr, STM32_DBGMCU_APB4_FZ1);
+    }
+#endif
+}
+
+#endif /* CONFIG_WATCHDOG && CONFIG_STM32H7_IWDG */
diff --git a/arch/arm/src/stm32h7/stm32_wdg.h b/arch/arm/src/stm32h7/stm32_wdg.h
new file mode 100644
index 0000000..06a0011
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_wdg.h
@@ -0,0 +1,119 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_wdg.h
+ *
+ *   Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved.
+ *   Author: Gregory Nutt <gn...@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_STM32_WDG_H
+#define __ARCH_ARM_SRC_STM32_STM32_WDG_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "hardware/stm32_wdg.h"
+
+#ifdef CONFIG_WATCHDOG
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_iwdginitialize
+ *
+ * Description:
+ *   Initialize the IWDG watchdog time.  The watchdog timer is initialized
+ *   and registers as 'devpath.  The initial state of the watchdog time is
+ *   disabled.
+ *
+ * Input Parameters:
+ *   devpath - The full path to the watchdog.  This should be of the form
+ *     /dev/watchdog0
+ *   lsifreq - The calibrated LSI clock frequency
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32H7_IWDG
+void stm32_iwdginitialize(FAR const char *devpath, uint32_t lsifreq);
+#endif
+
+/****************************************************************************
+ * Name: stm32_wwdginitialize
+ *
+ * Description:
+ *   Initialize the WWDG watchdog time.  The watchdog timer is initializeed and
+ *   registers as 'devpath.  The initial state of the watchdog time is
+ *   disabled.
+ *
+ * Input Parameters:
+ *   devpath - The full path to the watchdog.  This should be of the form
+ *     /dev/watchdog0
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32H7_WWDG
+void stm32_wwdginitialize(FAR const char *devpath);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_WATCHDOG */
+#endif /* __ARCH_ARM_SRC_STM32_STM32_WDG_H */
diff --git a/arch/arm/src/stm32h7/stm32_wwdg.c b/arch/arm/src/stm32h7/stm32_wwdg.c
new file mode 100644
index 0000000..c0d1083
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_wwdg.c
@@ -0,0 +1,798 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_wwdg.c
+ *
+ *   Copyright (C) 2012, 2016 Gregory Nutt. All rights reserved.
+ *   Author: Gregory Nutt <gn...@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+
+#include <stdint.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/timers/watchdog.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "stm32_wdg.h"
+
+#if defined(CONFIG_WATCHDOG) && defined(CONFIG_STM32H7_WWDG)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Clocking *****************************************************************/
+/* The minimum frequency of the WWDG clock is:
+ *
+ *  Fmin = PCLK1 / 4096 / 8
+ *
+ * So the maximum delay (in milliseconds) is then:
+ *
+ *   1000 * (WWDG_CR_T_MAX+1) / Fmin
+ *
+ * For example, if PCLK1 = 42MHz, then the maximum delay is:
+ *
+ *   Fmin = 1281.74
+ *   1000 * 64 / Fmin = 49.93 msec
+ */
+
+#define WWDG_FMIN       (STM32_PCLK1_FREQUENCY / 4096 / 8)
+#define WWDG_MAXTIMEOUT (1000 * (WWDG_CR_T_MAX+1) / WWDG_FMIN)
+
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_STM32H7_WWDG_DEFTIMOUT
+#  define CONFIG_STM32H7_WWDG_DEFTIMOUT WWDG_MAXTIMEOUT
+#endif
+
+#ifndef CONFIG_DEBUG_WATCHDOG_INFO
+#  undef CONFIG_STM32H7_WWDG_REGDEBUG
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+/* This structure provides the private representation of the "lower-half"
+ * driver state structure.  This structure must be cast-compatible with the
+ * well-known watchdog_lowerhalf_s structure.
+ */
+
+struct stm32_lowerhalf_s
+{
+  FAR const struct watchdog_ops_s  *ops;  /* Lower half operations */
+  xcpt_t   handler;  /* Current EWI interrupt handler */
+  uint32_t timeout;  /* The actual timeout value */
+  uint32_t fwwdg;    /* WWDG clock frequency */
+  bool     started;  /* The timer has been started */
+  uint8_t  reload;   /* The 7-bit reload field reset value */
+  uint8_t  window;   /* The 7-bit window (W) field value */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+/* Register operations ******************************************************/
+
+#ifdef CONFIG_STM32H7_WWDG_REGDEBUG
+static uint16_t stm32_getreg(uint32_t addr);
+static void     stm32_putreg(uint16_t val, uint32_t addr);
+#else
+# define        stm32_getreg(addr)     getreg32(addr)
+# define        stm32_putreg(val,addr) putreg32(val,addr)
+#endif
+static void     stm32_setwindow(FAR struct stm32_lowerhalf_s *priv,
+                  uint8_t window);
+
+/* Interrupt hanlding *******************************************************/
+
+static int      stm32_interrupt(int irq, FAR void *context, FAR void *arg);
+
+/* "Lower half" driver methods **********************************************/
+
+static int      stm32_start(FAR struct watchdog_lowerhalf_s *lower);
+static int      stm32_stop(FAR struct watchdog_lowerhalf_s *lower);
+static int      stm32_keepalive(FAR struct watchdog_lowerhalf_s *lower);
+static int      stm32_getstatus(FAR struct watchdog_lowerhalf_s *lower,
+                  FAR struct watchdog_status_s *status);
+static int      stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
+                  uint32_t timeout);
+static xcpt_t   stm32_capture(FAR struct watchdog_lowerhalf_s *lower,
+                  xcpt_t handler);
+static int      stm32_ioctl(FAR struct watchdog_lowerhalf_s *lower, int cmd,
+                  unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* "Lower half" driver methods */
+
+static const struct watchdog_ops_s g_wdgops =
+{
+  .start      = stm32_start,
+  .stop       = stm32_stop,
+  .keepalive  = stm32_keepalive,
+  .getstatus  = stm32_getstatus,
+  .settimeout = stm32_settimeout,
+  .capture    = stm32_capture,
+  .ioctl      = stm32_ioctl,
+};
+
+/* "Lower half" driver state */
+
+static struct stm32_lowerhalf_s g_wdgdev;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_getreg
+ *
+ * Description:
+ *   Get the contents of an STM32 register
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32H7_WWDG_REGDEBUG
+static uint16_t stm32_getreg(uint32_t addr)
+{
+  static uint32_t prevaddr = 0;
+  static uint32_t count = 0;
+  static uint16_t preval = 0;
+
+  /* Read the value from the register */
+
+  uint16_t val = getreg16(addr);
+
+  /* Is this the same value that we read from the same registe last time?  Are
+   * we polling the register?  If so, suppress some of the output.
+   */
+
+  if (addr == prevaddr && val == preval)
+    {
+      if (count == 0xffffffff || ++count > 3)
+        {
+          if (count == 4)
+            {
+              wdinfo("...\n");
+            }
+
+          return val;
+        }
+    }
+
+  /* No this is a new address or value */
+
+  else
+    {
+      /* Did we print "..." for the previous value? */
+
+      if (count > 3)
+        {
+          /* Yes.. then show how many times the value repeated */
+
+          wdinfo("[repeats %d more times]\n", count-3);
+        }
+
+      /* Save the new address, value, and count */
+
+      prevaddr = addr;
+      preval   = val;
+      count    = 1;
+    }
+
+  /* Show the register value read */
+
+  wdinfo("%08x->%04x\n", addr, val);
+  return val;
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_putreg
+ *
+ * Description:
+ *   Set the contents of an STM32 register to a value
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32H7_WWDG_REGDEBUG
+static void stm32_putreg(uint16_t val, uint32_t addr)
+{
+  /* Show the register value being written */
+
+  wdinfo("%08x<-%04x\n", addr, val);
+
+  /* Write the value */
+
+  putreg16(val, addr);
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_setwindow
+ *
+ * Description:
+ *   Set the CFR window value. The window value is compared to the down-
+ *   counter when the counter is updated.  The WWDG counter should be updated
+ *   only when the counter is below this window value (and greater than 64)
+ *   otherwise a reset will be generated
+ *
+ ****************************************************************************/
+
+static void stm32_setwindow(FAR struct stm32_lowerhalf_s *priv, uint8_t window)
+{
+  uint16_t regval;
+
+  /* Set W[6:0] bits according to selected window value */
+
+  regval = stm32_getreg(STM32_WWDG_CFR);
+  regval &= ~WWDG_CFR_W_MASK;
+  regval |= window << WWDG_CFR_W_SHIFT;
+  stm32_putreg(regval, STM32_WWDG_CFR);
+
+  /* Remember the window setting */
+
+  priv->window = window;
+}
+
+/****************************************************************************
+ * Name: stm32_interrupt
+ *
+ * Description:
+ *   WWDG early warning interrupt
+ *
+ * Input Parameters:
+ *   Usual interrupt handler arguments.
+ *
+ * Returned Value:
+ *   Always returns OK.
+ *
+ ****************************************************************************/
+
+static int stm32_interrupt(int irq, FAR void *context, FAR void *arg)
+{
+  FAR struct stm32_lowerhalf_s *priv = &g_wdgdev;
+  uint16_t regval;
+
+  /* Check if the EWI interrupt is really pending */
+
+  regval = stm32_getreg(STM32_WWDG_SR);
+  if ((regval & WWDG_SR_EWIF) != 0)
+    {
+      /* Is there a registered handler? */
+
+      if (priv->handler)
+        {
+          /* Yes... NOTE:  This interrupt service routine (ISR) must reload
+           * the WWDG counter to prevent the reset.  Otherwise, we will reset
+           * upon return.
+           */
+
+          priv->handler(irq, context, arg);
+        }
+
+      /* The EWI interrupt is cleared by writing '0' to the EWIF bit in the
+       * WWDG_SR register.
+       */
+
+      regval &= ~WWDG_SR_EWIF;
+      stm32_putreg(regval, STM32_WWDG_SR);
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_start
+ *
+ * Description:
+ *   Start the watchdog timer, resetting the time to the current timeout,
+ *
+ * Input Parameters:
+ *   lower - A pointer the publicly visible representation of the "lower-half"
+ *           driver state structure.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_start(FAR struct watchdog_lowerhalf_s *lower)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+
+  wdinfo("Entry\n");
+  DEBUGASSERT(priv);
+
+  /* The watchdog is always disabled after a reset. It is enabled by setting
+   * the WDGA bit in the WWDG_CR register, then it cannot be disabled again
+   * except by a reset.
+   */
+
+  stm32_putreg(WWDG_CR_WDGA | WWDG_CR_T_RESET | priv->reload, STM32_WWDG_CR);
+  priv->started = true;
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_stop
+ *
+ * Description:
+ *   Stop the watchdog timer
+ *
+ * Input Parameters:
+ *   lower - A pointer the publicly visible representation of the "lower-half"
+ *           driver state structure.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_stop(FAR struct watchdog_lowerhalf_s *lower)
+{
+  /* The watchdog is always disabled after a reset. It is enabled by setting
+   * the WDGA bit in the WWDG_CR register, then it cannot be disabled again
+   * except by a reset.
+   */
+
+  wdinfo("Entry\n");
+  return -ENOSYS;
+}
+
+/****************************************************************************
+ * Name: stm32_keepalive
+ *
+ * Description:
+ *   Reset the watchdog timer to the current timeout value, prevent any
+ *   imminent watchdog timeouts.  This is sometimes referred as "pinging"
+ *   the watchdog timer or "petting the dog".
+ *
+ *   The application program must write in the WWDG_CR register at regular
+ *   intervals during normal operation to prevent an MCU reset. This operation
+ *   must occur only when the counter value is lower than the window register
+ *   value. The value to be stored in the WWDG_CR register must be between
+ *   0xff and 0xC0:
+ *
+ * Input Parameters:
+ *   lower - A pointer the publicly visible representation of the "lower-half"
+ *           driver state structure.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_keepalive(FAR struct watchdog_lowerhalf_s *lower)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+
+  wdinfo("Entry\n");
+  DEBUGASSERT(priv);
+
+  /* Write to T[6:0] bits to configure the counter value, no need to do
+   * a read-modify-write; writing a 0 to WDGA bit does nothing.
+   */
+
+  stm32_putreg((WWDG_CR_T_RESET | priv->reload), STM32_WWDG_CR);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_getstatus
+ *
+ * Description:
+ *   Get the current watchdog timer status
+ *
+ * Input Parameters:
+ *   lower  - A pointer the publicly visible representation of the "lower-half"
+ *            driver state structure.
+ *   status - The location to return the watchdog status information.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_getstatus(FAR struct watchdog_lowerhalf_s *lower,
+                           FAR struct watchdog_status_s *status)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  uint32_t elapsed;
+  uint16_t reload;
+
+  wdinfo("Entry\n");
+  DEBUGASSERT(priv);
+
+  /* Return the status bit */
+
+  status->flags = WDFLAGS_RESET;
+  if (priv->started)
+    {
+      status->flags |= WDFLAGS_ACTIVE;
+    }
+
+  if (priv->handler)
+    {
+      status->flags |= WDFLAGS_CAPTURE;
+    }
+
+  /* Return the actual timeout is milliseconds */
+
+  status->timeout = priv->timeout;
+
+  /* Get the time remaining until the watchdog expires (in milliseconds) */
+
+  reload = (stm32_getreg(STM32_WWDG_CR) >> WWDG_CR_T_SHIFT) & 0x7f;
+  elapsed = priv->reload - reload;
+  status->timeleft = (priv->timeout * elapsed) / (priv->reload + 1);
+
+  wdinfo("Status     :\n");
+  wdinfo("  flags    : %08x\n", status->flags);
+  wdinfo("  timeout  : %d\n", status->timeout);
+  wdinfo("  timeleft : %d\n", status->flags);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_settimeout
+ *
+ * Description:
+ *   Set a new timeout value (and reset the watchdog timer)
+ *
+ * Input Parameters:
+ *   lower   - A pointer the publicly visible representation of the
+ *             "lower-half" driver state structure.
+ *   timeout - The new timeout value in milliseconds.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
+                            uint32_t timeout)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  uint32_t fwwdg;
+  uint32_t reload;
+  uint16_t regval;
+  int wdgtb;
+
+  DEBUGASSERT(priv);
+  wdinfo("Entry: timeout=%d\n", timeout);
+
+  /* Can this timeout be represented? */
+
+  if (timeout < 1 || timeout > WWDG_MAXTIMEOUT)
+    {
+      wderr("ERROR: Cannot represent timeout=%d > %d\n",
+            timeout, WWDG_MAXTIMEOUT);
+      return -ERANGE;
+    }
+
+  /* Determine prescaler value.
+   *
+   * Fwwdg = PCLK1/4096/prescaler.
+   *
+   * Where
+   *  Fwwwdg is the frequency of the WWDG clock
+   *  wdgtb is one of {1, 2, 4, or 8}
+   */
+
+  /* Select the smallest prescaler that will result in a reload field value that is
+   * less than the maximum.
+   */
+
+  for (wdgtb = 0; ; wdgtb++)
+    {
+      /* WDGTB = 0 -> Divider = 1  = 1 << 0
+       * WDGTB = 1 -> Divider = 2  = 1 << 1
+       * WDGTB = 2 -> Divider = 4  = 1 << 2
+       * WDGTB = 3 -> Divider = 8  = 1 << 3
+       */
+
+      /* Get the WWDG counter frequency in Hz. */
+
+      fwwdg = (STM32_PCLK1_FREQUENCY/4096) >> wdgtb;
+
+      /* The formula to calculate the timeout value is given by:
+       *
+       * timeout =  1000 * (reload + 1) / Fwwdg, OR
+       * reload = timeout * Fwwdg / 1000 - 1
+       *
+       * Where
+       *  timeout is the desired timout in milliseconds
+       *  reload is the contents of T{5:0]
+       *  Fwwdg is the frequency of the WWDG clock
+       */
+
+       reload = timeout * fwwdg / 1000 - 1;
+
+      /* If this reload valid is less than the maximum or we are not ready
+       * at the prescaler value, then break out of the loop to use these
+       * settings.
+       */
+
+#if 0
+      wdinfo("wdgtb=%d fwwdg=%d reload=%d timout=%d\n",
+             wdgtb, fwwdg, reload,  1000 * (reload + 1) / fwwdg);
+#endif
+      if (reload <= WWDG_CR_T_MAX || wdgtb == 3)
+        {
+          /* Note that we explicitly break out of the loop rather than using
+           * the 'for' loop termination logic because we do not want the
+           * value of wdgtb to be incremented.
+           */
+
+          break;
+        }
+    }
+
+  /* Make sure that the final reload value is within range */
+
+  if (reload > WWDG_CR_T_MAX)
+    {
+      reload = WWDG_CR_T_MAX;
+    }
+
+  /* Calculate and save the actual timeout value in milliseconds:
+   *
+   * timeout =  1000 * (reload + 1) / Fwwdg
+   */
+
+  priv->timeout = 1000 * (reload + 1) / fwwdg;
+
+  /* Remember the selected values */
+
+  priv->fwwdg  = fwwdg;
+  priv->reload = reload;
+
+  wdinfo("wdgtb=%d fwwdg=%d reload=%d timout=%d\n",
+         wdgtb, fwwdg, reload, priv->timeout);
+
+  /* Set WDGTB[1:0] bits according to calculated value */
+
+  regval = stm32_getreg(STM32_WWDG_CFR);
+  regval &= ~WWDG_CFR_WDGTB_MASK;
+  regval |= (uint16_t)wdgtb << WWDG_CFR_WDGTB_SHIFT;
+  stm32_putreg(regval, STM32_WWDG_CFR);
+
+  /* Reset the 7-bit window value to the maximum value.. essentially disabling
+   * the lower limit of the watchdog reset time.
+   */
+
+  stm32_setwindow(priv, 0x7f);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: stm32_capture
+ *
+ * Description:
+ *   Don't reset on watchdog timer timeout; instead, call this user provider
+ *   timeout handler.  NOTE:  Providing handler==NULL will restore the reset
+ *   behavior.
+ *
+ * Input Parameters:
+ *   lower      - A pointer the publicly visible representation of the "lower-half"
+ *                driver state structure.
+ *   newhandler - The new watchdog expiration function pointer.  If this
+ *                function pointer is NULL, then the reset-on-expiration
+ *                behavior is restored,
+ *
+ * Returned Value:
+ *   The previous watchdog expiration function pointer or NULL is there was
+ *   no previous function pointer, i.e., if the previous behavior was
+ *   reset-on-expiration (NULL is also returned if an error occurs).
+ *
+ ****************************************************************************/
+
+static xcpt_t stm32_capture(FAR struct watchdog_lowerhalf_s *lower,
+                            xcpt_t handler)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  irqstate_t flags;
+  xcpt_t oldhandler;
+  uint16_t regval;
+
+  DEBUGASSERT(priv);
+  wdinfo("Entry: handler=%p\n", handler);
+
+  /* Get the old handler return value */
+
+  flags = enter_critical_section();
+  oldhandler = priv->handler;
+
+  /* Save the new handler */
+
+   priv->handler = handler;
+
+  /* Are we attaching or detaching the handler? */
+
+  regval = stm32_getreg(STM32_WWDG_CFR);
+  if (handler)
+    {
+      /* Attaching... Enable the EWI interrupt */
+
+      regval |= WWDG_CFR_EWI;
+      stm32_putreg(regval, STM32_WWDG_CFR);
+
+      up_enable_irq(STM32_IRQ_WWDG1);
+    }
+  else
+    {
+      /* Detaching... Disable the EWI interrupt */
+
+      regval &= ~WWDG_CFR_EWI;
+      stm32_putreg(regval, STM32_WWDG_CFR);
+
+      up_disable_irq(STM32_IRQ_WWDG1);
+    }
+
+  leave_critical_section(flags);
+  return oldhandler;
+}
+
+/****************************************************************************
+ * Name: stm32_ioctl
+ *
+ * Description:
+ *   Any ioctl commands that are not recognized by the "upper-half" driver
+ *   are forwarded to the lower half driver through this method.
+ *
+ * Input Parameters:
+ *   lower - A pointer the publicly visible representation of the "lower-half"
+ *           driver state structure.
+ *   cmd   - The ioctl command value
+ *   arg   - The optional argument that accompanies the 'cmd'.  The
+ *           interpretation of this argument depends on the particular
+ *           command.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int stm32_ioctl(FAR struct watchdog_lowerhalf_s *lower, int cmd,
+                    unsigned long arg)
+{
+  FAR struct stm32_lowerhalf_s *priv = (FAR struct stm32_lowerhalf_s *)lower;
+  int ret = -ENOTTY;
+
+  DEBUGASSERT(priv);
+  wdinfo("Entry: cmd=%d arg=%ld\n", cmd, arg);
+
+  /* WDIOC_MINTIME: Set the minimum ping time.  If two keepalive ioctls
+   * are received within this time, a reset event will be generated.
+   * Argument: A 32-bit time value in milliseconds.
+   */
+
+  if (cmd == WDIOC_MINTIME)
+    {
+      uint32_t mintime = (uint32_t)arg;
+
+      /* The minimum time should be strictly less than the total delay
+       * which, in turn, will be less than or equal to WWDG_CR_T_MAX
+       */
+
+      ret = -EINVAL;
+      if (mintime < priv->timeout)
+        {
+          uint32_t window = (priv->timeout - mintime) * priv->fwwdg / 1000 - 1;
+          DEBUGASSERT(window < priv->reload);
+          stm32_setwindow(priv, window | WWDG_CR_T_RESET);
+          ret = OK;
+        }
+    }
+
+  return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_wwdginitialize
+ *
+ * Description:
+ *   Initialize the WWDG watchdog timer.  The watchdog timer is initialized and
+ *   registers as 'devpath'.  The initial state of the watchdog timer is
+ *   disabled.
+ *
+ * Input Parameters:
+ *   devpath - The full path to the watchdog.  This should be of the form
+ *     /dev/watchdog0
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_wwdginitialize(FAR const char *devpath)
+{
+  FAR struct stm32_lowerhalf_s *priv = &g_wdgdev;
+
+  wdinfo("Entry: devpath=%s\n", devpath);
+
+  /* NOTE we assume that clocking to the WWDG has already been provided by
+   * the RCC initialization logic.
+   */
+
+  /* Initialize the driver state structure.  Here we assume: (1) the state
+   * structure lies in .bss and was zeroed at reset time.  (2) This function
+   * is only called once so it is never necessary to re-zero the structure.
+   */
+
+  priv->ops = &g_wdgops;
+
+  /* Attach our EWI interrupt handler (But don't enable it yet) */
+
+  irq_attach(STM32_IRQ_WWDG1, stm32_interrupt, NULL);
+
+  /* Select an arbitrary initial timeout value.  But don't start the watchdog
+   * yet. NOTE: If the "Hardware watchdog" feature is enabled through the
+   * device option bits, the watchdog is automatically enabled at power-on.
+   */
+
+  stm32_settimeout((FAR struct watchdog_lowerhalf_s *)priv,
+                   CONFIG_STM32H7_WWDG_DEFTIMOUT);
+
+  /* Register the watchdog driver as /dev/watchdog0 */
+
+  watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv);
+
+  /* When the microcontroller enters debug mode (Cortex-M core halted),
+   * the WWDG counter either continues to work normally or stops, depending
+   * on the WWDG1 STOP configuration bit in DBG module.
+   */
+
+#if defined(CONFIG_STM32H7_JTAG_FULL_ENABLE) || \
+    defined(CONFIG_STM32H7_JTAG_NOJNTRST_ENABLE) || \
+    defined(CONFIG_STM32H7_JTAG_SW_ENABLE)
+    {
+      uint32_t cr = getreg32(STM32_DBGMCU_APB3_FZ1);
+      cr |= DBGMCU_APB3_WWDG1STOP;
+      putreg32(cr, STM32_DBGMCU_APB3_FZ1);
+    }
+#endif
+}
+
+#endif /* CONFIG_WATCHDOG && CONFIG_STM32H7_WWDG */


[incubator-nuttx] 01/13: STM32H7 ADC1 and ADC2 share some common registers. Added mbase and associated functions to driver to account for this.

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 8bb803e0e7e4549b269c81100795292ecfa995df
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Wed Jan 22 18:37:20 2020 -0600

    STM32H7 ADC1 and ADC2 share some common registers.  Added mbase and associated functions to driver to account for this.
---
 arch/arm/src/stm32h7/stm32_adc.c | 74 ++++++++++++++++++++++++++++++++++++++--
 1 file changed, 72 insertions(+), 2 deletions(-)

diff --git a/arch/arm/src/stm32h7/stm32_adc.c b/arch/arm/src/stm32h7/stm32_adc.c
index 7f0415e..9e758af 100644
--- a/arch/arm/src/stm32h7/stm32_adc.c
+++ b/arch/arm/src/stm32h7/stm32_adc.c
@@ -173,6 +173,8 @@ struct stm32_dev_s
   xcpt_t   isr;         /* Interrupt handler for this ADC block */
   uint32_t base;        /* Base address of registers unique to this ADC
                          * block */
+  uint32_t mbase;       /* Base address of master ADC (allows for access to
+                           shared common registers) */
 #ifdef ADC_HAVE_TIMER
   uint32_t tbase;       /* Base address of timer used by this ADC block */
   uint32_t trcc_enr;    /* RCC ENR Register */
@@ -297,6 +299,7 @@ static struct stm32_dev_s g_adcpriv1 =
   .isr         = adc12_interrupt,
   .intf        = 1,
   .base        = STM32_ADC1_BASE,
+  .mbase       = STM32_ADC1_BASE,
 #ifdef ADC1_HAVE_TIMER
   .trigger     = CONFIG_STM32H7_ADC1_TIMTRIG,
   .tbase       = ADC1_TIMER_BASE,
@@ -337,6 +340,7 @@ static struct stm32_dev_s g_adcpriv2 =
   .isr         = adc12_interrupt,
   .intf        = 2,
   .base        = STM32_ADC2_BASE,
+  .mbase       = STM32_ADC1_BASE,
 #ifdef ADC2_HAVE_TIMER
   .trigger     = CONFIG_STM32H7_ADC2_TIMTRIG,
   .tbase       = ADC2_TIMER_BASE,
@@ -377,6 +381,7 @@ static struct stm32_dev_s g_adcpriv3 =
   .isr         = adc3_interrupt,
   .intf        = 3,
   .base        = STM32_ADC3_BASE,
+  .mbase       = STM32_ADC3_BASE,
 #ifdef ADC3_HAVE_TIMER
   .trigger     = CONFIG_STM32H7_ADC3_TIMTRIG,
   .tbase       = ADC3_TIMER_BASE,
@@ -476,6 +481,71 @@ static void adc_modifyreg(FAR struct stm32_dev_s *priv, int offset,
 {
   adc_putreg(priv, offset, (adc_getreg(priv, offset) & ~clrbits) | setbits);
 }
+/****************************************************************************
+ * Name: adc_getregm
+ *
+ * Description:
+ *   Read the value of an ADC register from the associated ADC master.
+ *
+ * Input Parameters:
+ *   priv   - A reference to the ADC block status
+ *   offset - The offset to the register to read
+ *
+ * Returned Value:
+ *   The current contents of the specified register in the ADC master.
+ *
+ ****************************************************************************/
+
+static uint32_t adc_getregm(FAR struct stm32_dev_s *priv, int offset)
+{
+  return getreg32(priv->mbase + offset);
+}
+
+/****************************************************************************
+ * Name: adc_putregm
+ *
+ * Description:
+ *   Write a value to an ADC register in the associated ADC master.
+ *
+ * Input Parameters:
+ *   priv   - A reference to the ADC block status
+ *   offset - The offset to the register to write to
+ *   value  - The value to write to the register
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+static void adc_putregm(FAR struct stm32_dev_s *priv, int offset,
+                       uint32_t value)
+{
+  putreg32(value, priv->mbase + offset);
+}
+
+/****************************************************************************
+ * Name: adc_modifyregm
+ *
+ * Description:
+ *   Modify the value of an ADC register in the associated ADC master
+ *  (not atomic).
+ *
+ * Input Parameters:
+ *   priv    - A reference to the ADC block status
+ *   offset  - The offset to the register to modify
+ *   clrbits - The bits to clear
+ *   setbits - The bits to set
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+static void adc_modifyregm(FAR struct stm32_dev_s *priv, int offset,
+                          uint32_t clrbits, uint32_t setbits)
+{
+  adc_putregm(priv, offset, (adc_getregm(priv, offset) & ~clrbits) | setbits);
+}
 
 /****************************************************************************
  * Name: tim_getreg
@@ -1320,7 +1390,7 @@ static int adc_setup(FAR struct adc_dev_s *dev)
 
   adc_internal(priv, &setbits);
 
-  adc_modifyreg(priv, STM32_ADC_CCR_OFFSET, clrbits, setbits);
+  adc_modifyregm(priv, STM32_ADC_CCR_OFFSET, clrbits, setbits);
 
 #ifdef ADC_HAVE_DMA
 
@@ -1390,7 +1460,7 @@ static int adc_setup(FAR struct adc_dev_s *dev)
         adc_getreg(priv, STM32_ADC_SQR2_OFFSET),
         adc_getreg(priv, STM32_ADC_SQR3_OFFSET),
         adc_getreg(priv, STM32_ADC_SQR4_OFFSET));
-  ainfo("CCR:   0x%08x\n", getreg32(STM32_ADC_CCR));
+  ainfo("CCR:   0x%08x\n", adc_getregm(priv, STM32_ADC_CCR_OFFSET));
 
   /* Enable the ADC interrupt */
 


[incubator-nuttx] 04/13: Added basic power management (sleep/stop/standby) for STM32H7

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit ac654d9f2fcd64ec107b7dd47b6d211cea4970e7
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Tue Feb 4 17:51:43 2020 -0600

    Added basic power management (sleep/stop/standby) for STM32H7
---
 arch/arm/src/stm32h7/Make.defs                  |   7 ++
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h |  45 ++++++++-
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_rcc.h |  20 +++-
 arch/arm/src/stm32h7/stm32_pm.h                 | 122 +++++++++++++++++++++++
 arch/arm/src/stm32h7/stm32_pminitialize.c       |  78 +++++++++++++++
 arch/arm/src/stm32h7/stm32_pmsleep.c            | 101 +++++++++++++++++++
 arch/arm/src/stm32h7/stm32_pmstandby.c          |  99 +++++++++++++++++++
 arch/arm/src/stm32h7/stm32_pmstop.c             | 125 ++++++++++++++++++++++++
 8 files changed, 594 insertions(+), 3 deletions(-)

diff --git a/arch/arm/src/stm32h7/Make.defs b/arch/arm/src/stm32h7/Make.defs
index 965f38a..a8e37aa 100644
--- a/arch/arm/src/stm32h7/Make.defs
+++ b/arch/arm/src/stm32h7/Make.defs
@@ -210,3 +210,10 @@ endif
 ifeq ($(CONFIG_SENSORS_QENCODER),y)
 CHIP_CSRCS += stm32_qencoder.c
 endif
+
+ifeq ($(CONFIG_PM),y)
+CHIP_CSRCS += stm32_pmsleep.c stm32_pmstandby.c stm32_pmstop.c
+ifneq ($(CONFIG_ARCH_CUSTOM_PMINIT),y)
+CHIP_CSRCS += stm32_pminitialize.c
+endif
+endif
diff --git a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
index 693c0be..3c84e6b 100644
--- a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
+++ b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
@@ -89,7 +89,7 @@
 #define PWR_CR1_DBP               (1 << 8)   /* Bit 8: Disable backup domain write protection */
 #define PWR_CR1_FLPS              (1 << 9)   /* Bit 9: */
                                              /* Bits 10-13: Reserved */
-#define PWR_CR1_SVOS_SHIFT        (1 << 14)  /* Bits 14-15: */
+#define PWR_CR1_SVOS_SHIFT        (14)       /* Bits 14-15: */
 #define PWR_CR1_SVOS_MASK         (3 << PWR_CR1_SVOS_SHIFT)
                                                             /* 00: Reserved */
 #  define PWR_CR1_SVOS_S5         (1 << PWR_CR1_SVOS_SHIFT) /* 01:  */
@@ -161,11 +161,52 @@
 #  define PWR_D3CR_VOS_SCALE_0     (3 << STM32_PWR_D3CR_VOS_SHIFT) /* Fmax = 480MHz with ODN */
                                              /* Bits 15-31: Reserved */
 
-
 /* Power wakeup clear register (WKUPCR) */
 
+#define STM32_PWR_WKUPC1           (1 << 0)  /* Bit 0: Clear wakeup pin flag for WKUP1 */
+#define STM32_PWR_WKUPC2           (1 << 1)  /* Bit 1: Clear wakeup pin flag for WKUP2 */
+#define STM32_PWR_WKUPC3           (1 << 2)  /* Bit 2: Clear wakeup pin flag for WKUP3 */
+#define STM32_PWR_WKUPC4           (1 << 3)  /* Bit 3: Clear wakeup pin flag for WKUP4 */
+#define STM32_PWR_WKUPC5           (1 << 4)  /* Bit 4: Clear wakeup pin flag for WKUP5 */
+#define STM32_PWR_WKUPC6           (1 << 5)  /* Bit 5: Clear wakeup pin flag for WKUP6 */
+                                             /* Bits 6-31: Reserved */
+
 /* Power wakeup flag register (WKUPFR) */
 
+#define STM32_PWR_WKUPF1           (1 << 0)  /* Bit 0: Wakeup pin flag for WKUP1 */
+#define STM32_PWR_WKUPF2           (1 << 1)  /* Bit 1: Wakeup pin flag for WKUP2 */
+#define STM32_PWR_WKUPF3           (1 << 2)  /* Bit 2: Wakeup pin flag for WKUP3 */
+#define STM32_PWR_WKUPF4           (1 << 3)  /* Bit 3: Wakeup pin flag for WKUP4 */
+#define STM32_PWR_WKUPF5           (1 << 4)  /* Bit 4: Wakeup pin flag for WKUP5 */
+#define STM32_PWR_WKUPF6           (1 << 5)  /* Bit 5: Wakeup pin flag for WKUP6 */
+                                             /* Bits 6-31: Reserved */
+
 /* Power wakeup enable and polarity register (WKUPEPR) */
 
+#define STM32_PWR_WKUPEN1          (1 << 0)  /* Bit 0: Enable wakeup pin WKUP1 */
+#define STM32_PWR_WKUPEN2          (1 << 1)  /* Bit 1: Enable wakeup pin WKUP2 */
+#define STM32_PWR_WKUPEN3          (1 << 2)  /* Bit 2: Enable wakeup pin WKUP3 */
+#define STM32_PWR_WKUPEN4          (1 << 3)  /* Bit 3: Enable wakeup pin WKUP4 */
+#define STM32_PWR_WKUPEN5          (1 << 4)  /* Bit 4: Enable wakeup pin WKUP5 */
+#define STM32_PWR_WKUPEN6          (1 << 5)  /* Bit 5: Enable wakeup pin WKUP6 */
+                                             /* Bits 6-7: Reserved */
+#define STM32_PWR_WKUPP1           (1 << 8)  /* Bit 8: Wakeup pin polarity for WKUP1 */
+#define STM32_PWR_WKUPP2           (1 << 9)  /* Bit 9: Wakeup pin polarity for WKUP2 */
+#define STM32_PWR_WKUPP3           (1 << 10) /* Bit 10: Wakeup pin polarity for WKUP3 */
+#define STM32_PWR_WKUPP4           (1 << 11) /* Bit 11: Wakeup pin polarity for WKUP4 */
+#define STM32_PWR_WKUPP5           (1 << 12) /* Bit 12: Wakeup pin polarity for WKUP5 */
+#define STM32_PWR_WKUPP6           (1 << 13) /* Bit 13: Wakeup pin polarity for WKUP6 */
+                                             /* Bits 14-15: Reserved */
+#define STM32_PWR_WKUPPUPD1_SHIFT  (16)      /* Bits 16-17: Wakeup pin pull config for WKUP1 */
+#define STM32_PWR_WKUPPUPD2_SHIFT  (18)      /* Bits 18-19: Wakeup pin pull config for WKUP2 */
+#define STM32_PWR_WKUPPUPD3_SHIFT  (20)      /* Bits 20-21: Wakeup pin pull config for WKUP3 */
+#define STM32_PWR_WKUPPUPD4_SHIFT  (22)      /* Bits 22-23: Wakeup pin pull config for WKUP4 */
+#define STM32_PWR_WKUPPUPD5_SHIFT  (24)      /* Bits 24-25: Wakeup pin pull config for WKUP5 */
+#define STM32_PWR_WKUPPUPD6_SHIFT  (26)      /* Bits 26-27: Wakeup pin pull config for WKUP6 */
+# define STM32_PWR_WKUPPUPD_NONE    (0)      /* No pull-up */
+# define STM32_PWR_WKUPPUPD_PULLUP  (1)      /* Pull-up enabled */
+# define STM32_PWR_WKUPPUPD_PULLDN  (2)      /* Pull-down enabled */
+                                             /* 3 is reserved */
+                                             /* Bits 28-31: Reserved */
+
 #endif /* __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7X3XX_PWR_H */
diff --git a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_rcc.h b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_rcc.h
index dacd1ed..b4afa87 100644
--- a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_rcc.h
+++ b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_rcc.h
@@ -828,7 +828,25 @@
 
 /* TODO: D3 Autonomous mode register */
 
-/* TODO: RCC Reset Status register */
+/* RCC Reset Status register */
+
+                                                    /* Bits 0-15: Reserved */
+#define RCC_RSR_RMVF                    (1 << 16)   /* Bit 16: Remove reset flag */
+#define RCC_RSR_CPURSTF                 (1 << 17)   /* Bit 17: CPU reset flag */
+                                                    /* Bit 18: Reserved */
+#define RCC_RSR_D1RSTF                  (1 << 19)   /* Bit 19: D1 domain power switch reset flag */
+#define RCC_RSR_D2RSTF                  (1 << 20)   /* Bit 20: D2 domain power switch reset flag */
+#define RCC_RSR_BORRSTF                 (1 << 21)   /* Bit 21: BOR reset flag */
+#define RCC_RSR_PINRSTF                 (1 << 22)   /* Bit 22: Pin reset flag */
+#define RCC_RSR_PORRSTF                 (1 << 23)   /* Bit 23: POR/PDR reset flag */
+#define RCC_RSR_SFTRSTF                 (1 << 24)   /* Bit 24: System reset from CPU flag */
+                                                    /* Bit 25: Reserved */
+#define RCC_RSR_IWDG1RSTF               (1 << 26)   /* Bit 26: Independent watchdog reset flag */
+                                                    /* Bit 27: Reserved */
+#define RCC_RSR_WWDG1RSTF               (1 << 28)   /* Bit 28: Window watchdog reset flag */
+                                                    /* Bit 29: Reserved */
+#define RCC_RSR_LPWRRSTF                (1 << 30)   /* Bit 30: Reset due to illegal D1 DStandby or CPU Cstop flag */
+                                                    /* Bit 31: Reserved */
 
 /* AHB3 Peripheral Clock enable register */
 
diff --git a/arch/arm/src/stm32h7/stm32_pm.h b/arch/arm/src/stm32h7/stm32_pm.h
new file mode 100644
index 0000000..5339ffe
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_pm.h
@@ -0,0 +1,122 @@
+/************************************************************************************
+ * arch/arm/src/stm32h7/stm32_pm.h
+ *
+ *   Copyright (C) 2018 Haltian Ltd. All rights reserved.
+ *   Author: Juha Niskanen <ju...@haltian.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32H7_STM32_PM_H
+#define __ARCH_ARM_SRC_STM32H7_STM32_PM_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "chip.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Name: stm32_pmstop
+ *
+ * Description:
+ *   Enter STOP mode.
+ *
+ * Input Parameters:
+ *   lpds - true: To further reduce power consumption in Stop mode, put the
+ *          internal voltage regulator in low-power under-drive mode using the
+ *          LPDS and LPUDS bits of the Power control register (PWR_CR1).
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_pmstop(bool lpds);
+
+/****************************************************************************
+ * Name: stm32_pmstandby
+ *
+ * Description:
+ *   Enter STANDBY mode.
+ *
+ * Input Parameters:
+ *   None
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_pmstandby(void);
+
+/****************************************************************************
+ * Name: stm32_pmsleep
+ *
+ * Description:
+ *   Enter SLEEP mode.
+ *
+ * Input Parameters:
+ *   sleeponexit - true:  SLEEPONEXIT bit is set when the WFI instruction is
+ *                        executed, the MCU enters Sleep mode as soon as it
+ *                        exits the lowest priority ISR.
+ *               - false: SLEEPONEXIT bit is cleared, the MCU enters Sleep mode
+ *                        as soon as WFI or WFE instruction is executed.
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_pmsleep(bool sleeponexit);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
+#endif /* __ARCH_ARM_SRC_STM32H7_STM32_PM_H */
diff --git a/arch/arm/src/stm32h7/stm32_pminitialize.c b/arch/arm/src/stm32h7/stm32_pminitialize.c
new file mode 100644
index 0000000..ffcd5d0
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_pminitialize.c
@@ -0,0 +1,78 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_pminitialize.c
+ *
+ *   Copyright (C) 2012, 2017 Gregory Nutt. All rights reserved.
+ *   Author: Gregory Nutt <gn...@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/power/pm.h>
+
+#include "up_internal.h"
+#include "stm32_pm.h"
+
+#ifdef CONFIG_PM
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_pminitialize
+ *
+ * Description:
+ *   This function is called by MCU-specific logic at power-on reset in
+ *   order to provide one-time initialization the power management subsystem.
+ *   This function must be called *very* early in the initialization sequence
+ *   *before* any other device drivers are initialized (since they may
+ *   attempt to register with the power management subsystem).
+ *
+ * Input Parameters:
+ *   None.
+ *
+ * Returned Value:
+ *   None.
+ *
+ ****************************************************************************/
+
+void up_pminitialize(void)
+{
+  /* Then initialize the NuttX power management subsystem proper */
+
+  pm_initialize();
+}
+
+#endif /* CONFIG_PM */
diff --git a/arch/arm/src/stm32h7/stm32_pmsleep.c b/arch/arm/src/stm32h7/stm32_pmsleep.c
new file mode 100644
index 0000000..b7c92e4
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_pmsleep.c
@@ -0,0 +1,101 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_pmsleep.c
+ *
+ *   Copyright (C) 2012, 2017 Gregory Nutt. All rights reserved.
+ *   Authors: Gregory Nutt <gn...@nuttx.org>
+ *            Diego Sanchez <ds...@nx-engineering.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "up_arch.h"
+#include "nvic.h"
+#include "stm32_pwr.h"
+#include "stm32_pm.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_pmsleep
+ *
+ * Description:
+ *   Enter SLEEP mode.
+ *
+ * Input Parameters:
+ *   sleeponexit - true:  SLEEPONEXIT bit is set when the WFI instruction is
+ *                        executed, the MCU enters Sleep mode as soon as it
+ *                        exits the lowest priority ISR.
+ *               - false: SLEEPONEXIT bit is cleared, the MCU enters Sleep mode
+ *                        as soon as WFI or WFE instruction is executed.
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_pmsleep(bool sleeponexit)
+{
+  uint32_t regval;
+
+  /* Clear SLEEPDEEP bit of Cortex System Control Register */
+
+  regval  = getreg32(NVIC_SYSCON);
+  regval &= ~NVIC_SYSCON_SLEEPDEEP;
+  if (sleeponexit)
+    {
+      regval |= NVIC_SYSCON_SLEEPONEXIT;
+    }
+  else
+    {
+      regval &= ~NVIC_SYSCON_SLEEPONEXIT;
+    }
+
+  putreg32(regval, NVIC_SYSCON);
+
+  /* Sleep until the wakeup interrupt or event occurs */
+
+#ifdef CONFIG_PM_WFE
+  /* Mode: SLEEP + Entry with WFE */
+
+  asm("wfe");
+#else
+  /* Mode: SLEEP + Entry with WFI */
+
+  asm("wfi");
+#endif
+}
diff --git a/arch/arm/src/stm32h7/stm32_pmstandby.c b/arch/arm/src/stm32h7/stm32_pmstandby.c
new file mode 100644
index 0000000..2486e1c
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_pmstandby.c
@@ -0,0 +1,99 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_pmstandby.c
+ *
+ *   Copyright (C) 2018 Haltian Ltd. All rights reserved.
+ *   Author: Juha Niskanen <ju...@haltian.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "up_arch.h"
+#include "nvic.h"
+#include "stm32_rcc.h"
+#include "stm32_pwr.h"
+#include "stm32_pm.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_pmstandby
+ *
+ * Description:
+ *   Enter STANDBY mode.
+ *
+ * Input Parameters:
+ *   None
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_pmstandby(void)
+{
+  uint32_t regval;
+
+  /* Clear the wake-up flags before reseting. */
+
+  modifyreg32(STM32_PWR_CPUCR, 0, STM32_PWR_CPUCR_CSSF);
+  modifyreg32(STM32_PWR_WKUPCR, 0, STM32_PWR_WKUPC1 | STM32_PWR_WKUPC2 |
+                                   STM32_PWR_WKUPC3 | STM32_PWR_WKUPC4 |
+                                   STM32_PWR_WKUPC5 | STM32_PWR_WKUPC6);
+
+  /* Clear reset flags. */
+
+  modifyreg32(STM32_RCC_CSR, 0, RCC_RSR_RMVF);
+
+  /* Set the domain Power Down Deep Sleep (PDDS) bits in the power control register.
+   * so that D1, D2, and D3 will go into the DStop state. */
+
+  modifyreg32(STM32_PWR_CPUCR, 0, STM32_PWR_CPUCR_PDDS_D1 |
+                                  STM32_PWR_CPUCR_PDDS_D2 |
+                                  STM32_PWR_CPUCR_PDDS_D3);
+
+  /* Set SLEEPDEEP bit of Cortex System Control Register */
+
+  regval  = getreg32(NVIC_SYSCON);
+  regval |= NVIC_SYSCON_SLEEPDEEP;
+  putreg32(regval, NVIC_SYSCON);
+
+  /* Sleep until the wakeup reset occurs */
+
+  asm("wfi");
+}
diff --git a/arch/arm/src/stm32h7/stm32_pmstop.c b/arch/arm/src/stm32h7/stm32_pmstop.c
new file mode 100644
index 0000000..6159e8c
--- /dev/null
+++ b/arch/arm/src/stm32h7/stm32_pmstop.c
@@ -0,0 +1,125 @@
+/****************************************************************************
+ * arch/arm/src/stm32h7/stm32_pmstop.c
+ *
+ *   Copyright (C) 2018 Haltian Ltd. All rights reserved.
+ *   Author: Juha Niskanen <ju...@haltian.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ *    used to endorse or promote products derived from this software
+ *    without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "up_arch.h"
+#include "nvic.h"
+#include "stm32_pwr.h"
+#include "stm32_pm.h"
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_pmstop
+ *
+ * Description:
+ *   Enter STOP mode.
+ *
+ * Input Parameters:
+ *   lpds - true: To further reduce power consumption in Stop mode, put the
+ *          internal voltage regulator in low-power under-drive mode using the
+ *          LPDS and LPUDS bits of the Power control register (PWR_CR1).
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void stm32_pmstop(bool lpds)
+{
+  uint32_t regval;
+
+  /* Clear the Low Power Deep Sleep (LPDS) bit in the CPU power control register.
+   */
+
+  regval  = getreg32(STM32_PWR_CR1);
+  regval &= ~(PWR_CR1_LPDS | PWR_CR1_SVOS_MASK);
+
+  /* Set low-power regulator mode and voltage scaling.  */
+
+  if (lpds)
+    {
+      regval |= PWR_CR1_LPDS | PWR_CR1_SVOS_S5;
+    }
+  else
+    {
+      /* Set regulator to normal (S3) mode */
+
+      regval |= PWR_CR1_SVOS_S3;
+    }
+
+  putreg32(regval, STM32_PWR_CR1);
+
+  /* Clear the domain standby bits so D1, D2 and D3 remain in DStop mode */
+
+  regval  = getreg32(STM32_PWR_CPUCR);
+  regval &= ~(STM32_PWR_CPUCR_PDDS_D1 | STM32_PWR_CPUCR_PDDS_D2 | STM32_PWR_CPUCR_PDDS_D3);
+  putreg32(regval, STM32_PWR_CPUCR);
+
+  /* Set SLEEPDEEP bit of Cortex System Control Register */
+
+  regval  = getreg32(NVIC_SYSCON);
+  regval |= NVIC_SYSCON_SLEEPDEEP;
+  putreg32(regval, NVIC_SYSCON);
+
+  /* Sleep until the wakeup interrupt or event occurs */
+
+#ifdef CONFIG_PM_WFE
+  /* Mode: SLEEP + Entry with WFE */
+
+  asm volatile ("wfe");
+#else
+  /* Mode: SLEEP + Entry with WFI */
+
+  asm volatile ("wfi");
+#endif
+
+  /* Clear deep sleep bits, so that MCU does not go into deep sleep in idle. */
+
+  /* Clear SLEEPDEEP bit of Cortex System Control Register */
+
+  regval  = getreg32(NVIC_SYSCON);
+  regval &= ~NVIC_SYSCON_SLEEPDEEP;
+  putreg32(regval, NVIC_SYSCON);
+}


[incubator-nuttx] 11/13: Fixed compiler warning about possibly uninitialized variable.

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 115ccf5a5ce9e4fb0c59f274f56b24be99db9dab
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Fri Feb 21 14:06:57 2020 -0600

    Fixed compiler warning about possibly uninitialized variable.
---
 arch/arm/src/stm32h7/stm32_ethernet.c | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/arch/arm/src/stm32h7/stm32_ethernet.c b/arch/arm/src/stm32h7/stm32_ethernet.c
index e2002f8..a3d1974 100644
--- a/arch/arm/src/stm32h7/stm32_ethernet.c
+++ b/arch/arm/src/stm32h7/stm32_ethernet.c
@@ -1660,7 +1660,7 @@ static void stm32_freesegment(struct stm32_ethmac_s *priv,
 static int stm32_recvframe(struct stm32_ethmac_s *priv)
 {
   struct eth_desc_s *rxdesc;
-  struct eth_desc_s *rxcurr;
+  struct eth_desc_s *rxcurr = NULL;
   uint8_t *buffer;
   int i;
 
@@ -1818,6 +1818,7 @@ static int stm32_recvframe(struct stm32_ethmac_s *priv)
         {
           /* Drop the context descriptors, we are not interested */
 
+          DEBUGASSERT(rxcurr != NULL);
           stm32_freesegment(priv, rxcurr, 1);
         }
 


[incubator-nuttx] 07/13: Fix PCSEL setup on STM32H7 ADC

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 5d2b433edd12f3464e5f648d1c730dd243d4b729
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Mon Feb 10 13:47:29 2020 -0600

    Fix PCSEL setup on STM32H7 ADC
---
 arch/arm/src/stm32h7/stm32_adc.c | 4 +++-
 1 file changed, 3 insertions(+), 1 deletion(-)

diff --git a/arch/arm/src/stm32h7/stm32_adc.c b/arch/arm/src/stm32h7/stm32_adc.c
index c3e6975..9f135bf 100644
--- a/arch/arm/src/stm32h7/stm32_adc.c
+++ b/arch/arm/src/stm32h7/stm32_adc.c
@@ -1438,11 +1438,13 @@ static int adc_setup(FAR struct adc_dev_s *dev)
 
   setbits = 0;
   clrbits = ADC_PCSEL_PCSEL_ALL;
-  for (i = 0; i < priv->cchannels && priv->chanlist[i]; i++)
+  for (i = 0; i < priv->cchannels; i++)
     {
       setbits |= 1 << priv->chanlist[i];
     }
 
+  setbits &= ADC_PCSEL_PCSEL_ALL;
+
   adc_modifyreg(priv, STM32_ADC_PCSEL_OFFSET, clrbits, setbits);
 
 


[incubator-nuttx] 12/13: Added configuration function for onboard VBAT charger in STM32H7

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 96cec9c5c79d31267d6756ef4f3fb41075e92cca
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Mon Feb 24 12:00:50 2020 -0600

    Added configuration function for onboard VBAT charger in STM32H7
---
 arch/arm/src/stm32h7/stm32_pwr.c | 48 ++++++++++++++++++++++++++++++++++++++++
 arch/arm/src/stm32h7/stm32_pwr.h | 18 +++++++++++++++
 2 files changed, 66 insertions(+)

diff --git a/arch/arm/src/stm32h7/stm32_pwr.c b/arch/arm/src/stm32h7/stm32_pwr.c
index a676227..0ae5051 100644
--- a/arch/arm/src/stm32h7/stm32_pwr.c
+++ b/arch/arm/src/stm32h7/stm32_pwr.c
@@ -383,4 +383,52 @@ void stm32_pwr_configurewkup(uint32_t pin, bool en, bool rising, uint32_t pull)
 
   leave_critical_section(flags);
 }
+
+/************************************************************************************
+ * Name: stm32_pwr_setvbatcharge
+ *
+ * Description:
+ *   Configures the internal charge resistor to charge a battery attached to
+ *   the VBAT pin.
+ *
+ *
+ * Input Parameters:
+ *   enable    - Enables the charge resistor if true, disables it if false
+ *   resistor  - Sets charge resistor to 1.5 KOhm if true, sets it to 5 KOhm if false.
+ *
+ * Returned Value:
+ *   None
+ *
+ ************************************************************************************/
+void stm32_pwr_setvbatcharge(bool enable, bool resistor)
+{
+  irqstate_t flags;
+  uint32_t regval;
+
+  flags = enter_critical_section();
+
+  regval      = stm32_pwr_getreg(STM32_PWR_CR3_OFFSET);
+
+  if (enable)
+    {
+      regval |= STM32_PWR_CR3_VBE;
+    }
+  else
+    {
+      regval &= ~STM32_PWR_CR3_VBE;
+    }
+
+  if (resistor)
+    {
+      regval |= STM32_PWR_CR3_VBRS;
+    }
+  else
+    {
+      regval &= ~STM32_PWR_CR3_VBRS;
+    }
+
+  stm32_pwr_putreg(STM32_PWR_CR3_OFFSET, regval);
+
+  leave_critical_section(flags);
+}
 #endif /* CONFIG_STM32_PWR */
diff --git a/arch/arm/src/stm32h7/stm32_pwr.h b/arch/arm/src/stm32h7/stm32_pwr.h
index 761c158..5b753e6 100644
--- a/arch/arm/src/stm32h7/stm32_pwr.h
+++ b/arch/arm/src/stm32h7/stm32_pwr.h
@@ -148,6 +148,24 @@ void stm32_pwr_enablebreg(bool region);
 
 void stm32_pwr_configurewkup(uint32_t pin, bool en, bool rising, uint32_t pull);
 
+/************************************************************************************
+ * Name: stm32_pwr_setvbatcharge
+ *
+ * Description:
+ *   Configures the internal charge resistor to charge a battery attached to
+ *   the VBAT pin.
+ *
+ *
+ * Input Parameters:
+ *   enable    - Enables the charge resistor if true, disables it if false
+ *   resistor  - Sets charge resistor to 1.5 KOhm if true, sets it to 5 KOhm if false.
+ *
+ * Returned Value:
+ *   None
+ *
+ ************************************************************************************/
+void stm32_pwr_setvbatcharge(bool enable, bool resistor);
+
 #undef EXTERN
 #if defined(__cplusplus)
 }


[incubator-nuttx] 10/13: Updated STM32H7 startup with check for ACTVOSRDY per recommendation in reference manual.

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit f7577e204ab02943043526c661b94494b475c087
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Fri Feb 21 14:06:05 2020 -0600

    Updated STM32H7 startup with check for ACTVOSRDY per recommendation in reference manual.
---
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h | 15 +++++++++++++--
 arch/arm/src/stm32h7/stm32h7x3xx_rcc.c          |  5 +++++
 2 files changed, 18 insertions(+), 2 deletions(-)

diff --git a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
index 647dbf7..7cae78c 100644
--- a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
+++ b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
@@ -104,8 +104,19 @@
 #  define PWR_CR1_ALS_2V8           (3 << PWR_CR1_ALS_SHIFT) /* 11: */
                                               /* Bits 19-31: Reserved */
 
-/* Power control/status register 1 (CRS1) */
-
+/* Power control/status register 1 (CSR1) */
+                                              /* Bits 0-3: Reserved */
+#define PWR_CSR1_PVDO               (1 << 4)  /* Bit 4: Programmable voltage detect output*/
+                                              /* Bits 5-12: Reserved */
+#define PWR_CSR1_ACTVOSRDY          (1 << 13) /* Bit 13: VOS voltage level ready */
+#define PWR_CSR1_ACTVOS_SHIFT       (14)      /* Bits 14-15: Current VOS applied */
+#  define PWR_CSR1_VOS_SCALE_3R     (0 << PWR_CSR1_ACTVOS_SHIFT)
+#  define PWR_CSR1_VOS_SCALE_3      (1 << PWR_CSR1_ACTVOS_SHIFT)
+#  define PWR_CSR1_VOS_SCALE_2      (2 << PWR_CSR1_ACTVOS_SHIFT)
+#  define PWR_CSR1_VOS_SCALE_1      (3 << PWR_CSR1_ACTVOS_SHIFT)
+#  define PWR_CSR1_VOS_SCALE_0      (3 << PWR_CSR1_ACTVOS_SHIFT)
+#define PWR_CSR1_AVDO               (1 << 16) /* Bit 16: Analog voltage detector output */
+                                              /* Bits 17-31: Reserved */
 /* Power control register 2 (CR2) */
 
 #define PWR_CR2_BREN                (1 << 0)   /* Bit 0: Backup regulator enable */
diff --git a/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c b/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c
index 54f3f8f..536b225 100644
--- a/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c
+++ b/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c
@@ -804,6 +804,11 @@ static void stm32_stdclockconfig(void)
         {
         }
 
+      /* See Reference manual Section 5.4.1, System supply startup */
+      while ((getreg32(STM32_PWR_CSR1) & PWR_CSR1_ACTVOSRDY) == 0)
+        {
+        }
+
       /* Over-drive is needed if
        *  - Voltage output scale 1 mode is selected and SYSCLK frequency is
        *    over 400 Mhz.


[incubator-nuttx] 13/13: Clean up comments and formatting

Posted by ac...@apache.org.
This is an automated email from the ASF dual-hosted git repository.

acassis pushed a commit to branch pr402
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git

commit 17985a296d99be7f6e7fdbe9dd40e10f8c36c579
Author: Joshua Lange <jl...@2g-eng.com>
AuthorDate: Fri Feb 28 13:08:19 2020 -0600

    Clean up comments and formatting
---
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h | 14 ++--
 arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h   |  2 +-
 arch/arm/src/stm32h7/stm32_adc.c                  | 43 +++++++-----
 arch/arm/src/stm32h7/stm32_ethernet.c             | 62 +++++++++---------
 arch/arm/src/stm32h7/stm32_ethernet.h             |  4 +-
 arch/arm/src/stm32h7/stm32_flash.c                | 80 +++++++++++++----------
 arch/arm/src/stm32h7/stm32_flash.h                |  4 +-
 arch/arm/src/stm32h7/stm32_iwdg.c                 | 61 +++++++++--------
 arch/arm/src/stm32h7/stm32_pm.h                   | 12 ++--
 arch/arm/src/stm32h7/stm32_pminitialize.c         |  2 +-
 arch/arm/src/stm32h7/stm32_pmsleep.c              |  6 +-
 arch/arm/src/stm32h7/stm32_pmstandby.c            |  5 +-
 arch/arm/src/stm32h7/stm32_pmstop.c               | 10 +--
 arch/arm/src/stm32h7/stm32_pwr.c                  | 17 +++--
 arch/arm/src/stm32h7/stm32_pwr.h                  | 17 +++--
 arch/arm/src/stm32h7/stm32_wdg.h                  | 10 +--
 arch/arm/src/stm32h7/stm32_wwdg.c                 | 63 ++++++++++--------
 arch/arm/src/stm32h7/stm32h7x3xx_rcc.c            | 17 +++--
 18 files changed, 237 insertions(+), 192 deletions(-)

diff --git a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h
index 976c67a..aa29308 100644
--- a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h
+++ b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h
@@ -1,4 +1,4 @@
-/******************************************************************************
+/****************************************************************************
  * arch/arm/src/stm32h7/hardware/stm32h7x3xx_flash.h
  *
  *   Copyright (C) 2018 Gregory Nutt. All rights reserved.
@@ -31,16 +31,16 @@
  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  * POSSIBILITY OF SUCH DAMAGE.
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 #ifndef __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7X3XX_FLASH_H
 #define __ARCH_ARM_SRC_STM32H7_HARDWARE_STM32H7X3XX_FLASH_H
 
-/******************************************************************************
+/****************************************************************************
  * Pre-processor Definitions
- *****************************************************************************/
+ ****************************************************************************/
 
-/* Register Offsets *****************************************************************/
+/* Register Offsets *********************************************************/
 
 #define STM32_FLASH_ACR_OFFSET         0x0000 /* Access control register */
 #define STM32_FLASH_KEYR1_OFFSET       0x0004 /* Key register for bank 1 */
@@ -84,7 +84,7 @@
 #define STM32_FLASH_BANK1_OFFSET       0x0000 /* Bank 1 registers offset */
 #define STM32_FLASH_BANK2_OFFSET       0x0100 /* Bank 2 registers offset */
 
-/* Register Addresses ***************************************************************/
+/* Register Addresses *******************************************************/
 
 #define STM32_FLASH_ACR                (STM32_FLASHIF_BASE + STM32_FLASH_ACR_OFFSET)
 #define STM32_FLASH_KEYR1              (STM32_FLASHIF_BASE + STM32_FLASH_KEYR1_OFFSET)
@@ -125,7 +125,7 @@
 #define STM32_FLASH_CRCEADD2R          (STM32_FLASHIF_BASE + STM32_FLASH_CRCEADD2R_OFFSET)
 #define STM32_FLASH_ECC_FA2R           (STM32_FLASHIF_BASE + STM32_FLASH_ECC_FA2R_OFFSET)
 
-/* Register Bitfield Definitions ****************************************************/
+/* Register Bitfield Definitions ********************************************/
 
 /* Flash Access Control Register (ACR) Bank 1 or 2 */
 
diff --git a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
index 7cae78c..13509ef 100644
--- a/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
+++ b/arch/arm/src/stm32h7/hardware/stm32h7x3xx_pwr.h
@@ -75,7 +75,6 @@
                                                 /* Bits 1-3: Reserved */
 #define PWR_CR1_PVDE                (1 << 4)    /* Bit 4: Programmable voltage detector enable */
 
-
 #define PWR_CR1_PLS_SHIFT           (5)        /* Bits 5-7: Programmable voltage detector level */
 #define PWR_CR1_PLS_MASK            (7 << PWR_CR1_PLS_SHIFT)
 #  define PWR_CR1_PLS_1V95          (0 << PWR_CR1_PLS_SHIFT) /* 000: */
@@ -105,6 +104,7 @@
                                               /* Bits 19-31: Reserved */
 
 /* Power control/status register 1 (CSR1) */
+
                                               /* Bits 0-3: Reserved */
 #define PWR_CSR1_PVDO               (1 << 4)  /* Bit 4: Programmable voltage detect output*/
                                               /* Bits 5-12: Reserved */
diff --git a/arch/arm/src/stm32h7/stm32_adc.c b/arch/arm/src/stm32h7/stm32_adc.c
index 9f135bf..db2290b 100644
--- a/arch/arm/src/stm32h7/stm32_adc.c
+++ b/arch/arm/src/stm32h7/stm32_adc.c
@@ -86,7 +86,8 @@
           ((type *)((intptr_t)(ptr) - offsetof(type, member)))
 #endif
 
-/* ADC Channels/DMA ********************************************************/
+/* ADC Channels/DMA *********************************************************/
+
 /* The maximum number of channels that can be sampled.  While DMA support is
  * very nice for reliable multi-channel sampling, the STM32H7 can function
  * without, although there is a risk of overrun.
@@ -174,7 +175,7 @@ struct stm32_dev_s
   uint32_t base;        /* Base address of registers unique to this ADC
                          * block */
   uint32_t mbase;       /* Base address of master ADC (allows for access to
-                           shared common registers) */
+                         * shared common registers) */
   bool     initialized; /* Keeps track of the initialization status of the ADC */
 #ifdef ADC_HAVE_TIMER
   uint32_t tbase;       /* Base address of timer used by this ADC block */
@@ -228,10 +229,11 @@ static void     tim_dumpregs(FAR struct stm32_dev_s *priv,
 
 static void adc_rccreset(FAR struct stm32_dev_s *priv, bool reset);
 static void adc_enable(FAR struct stm32_dev_s *priv);
-static uint32_t adc_sqrbits(FAR struct stm32_dev_s *priv, int first, int last,
-                            int offset);
+static uint32_t adc_sqrbits(FAR struct stm32_dev_s *priv, int first,
+                            int last, int offset);
 static int      adc_set_ch(FAR struct adc_dev_s *dev, uint8_t ch);
-static bool     adc_internal(FAR struct stm32_dev_s * priv, uint32_t *adc_ccr);
+static bool     adc_internal(FAR struct stm32_dev_s * priv,
+                             uint32_t *adc_ccr);
 
 #ifdef ADC_HAVE_TIMER
 static void adc_timstart(FAR struct stm32_dev_s *priv, bool enable);
@@ -485,6 +487,7 @@ static void adc_modifyreg(FAR struct stm32_dev_s *priv, int offset,
 {
   adc_putreg(priv, offset, (adc_getreg(priv, offset) & ~clrbits) | setbits);
 }
+
 /****************************************************************************
  * Name: adc_getregm
  *
@@ -848,7 +851,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
 
   /* Set the reload and prescaler values */
 
-  tim_putreg(priv, STM32_GTIM_PSC_OFFSET, prescaler-1);
+  tim_putreg(priv, STM32_GTIM_PSC_OFFSET, prescaler - 1);
   tim_putreg(priv, STM32_GTIM_ARR_OFFSET, reload);
 
   /* Clear the advanced timers repetition counter in TIM1 */
@@ -949,6 +952,7 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
       case 4: /* TimerX TRGO event */
         {
           /* TODO: TRGO support not yet implemented */
+
           /* Set the event TRGO */
 
           ccenable = 0;
@@ -1053,9 +1057,11 @@ static int adc_timinit(FAR struct stm32_dev_s *priv)
  *
  * Description:
  *   Called by power management framework when it wants to enter low power
- *   states. Check if ADC is in progress and if so prevent from entering STOP.
+ *   states. Check if ADC is in progress and if so prevent from entering
+ *   STOP.
  *
  ****************************************************************************/
+
 #ifdef CONFIG_PM
 static int adc_pm_prepare(struct pm_callback_s *cb, int domain,
                           enum pm_state_e state)
@@ -1167,7 +1173,7 @@ static void adc_rccreset(FAR struct stm32_dev_s *priv, bool reset)
       bit = RCC_AHB1RSTR_ADC12RST;
     }
 
-   /* First must disable interrupts because the AHB2RSTR register is used by
+  /* First must disable interrupts because the AHB2RSTR register is used by
    * several different drivers.
    */
 
@@ -1249,8 +1255,8 @@ static void adc_enable(FAR struct stm32_dev_s *priv)
  * Name: adc_bind
  *
  * Description:
- *   Bind the upper-half driver callbacks to the lower-half implementation.  This
- *   must be called early in order to receive ADC event notifications.
+ *   Bind the upper-half driver callbacks to the lower-half implementation.
+ *   This must be called early in order to receive ADC event notifications.
  *
  ****************************************************************************/
 
@@ -1332,15 +1338,16 @@ static int adc_setup(FAR struct adc_dev_s *dev)
    * other has already been reset. (We only need to worry about this if both
    * ADC1 and ADC2 are enabled.)
    */
+
 #if defined(CONFIG_STM32H7_ADC1) && defined(CONFIG_STM32H7_ADC2)
   if ((dev == &g_adcdev1 &&
       !((FAR struct stm32_dev_s *)g_adcdev2.ad_priv)->initialized) ||
      (dev == &g_adcdev2 &&
       !((FAR struct stm32_dev_s *)g_adcdev1.ad_priv)->initialized))
 #endif
-  {
-     adc_reset(dev);
-  }
+    {
+      adc_reset(dev);
+    }
 
   /* Initialize the same sample time for each ADC.
    * During sample cycles channel selection bits must remain unchanged.
@@ -1447,7 +1454,6 @@ static int adc_setup(FAR struct adc_dev_s *dev)
 
   adc_modifyreg(priv, STM32_ADC_PCSEL_OFFSET, clrbits, setbits);
 
-
   /* Set ADEN to wake up the ADC from Power Down. */
 
   adc_enable(priv);
@@ -1554,6 +1560,7 @@ static void adc_rxint(FAR struct adc_dev_s *dev, bool enable)
 
       regval &= ~ADC_INT_MASK;
     }
+
   adc_putreg(priv, STM32_ADC_IER_OFFSET, regval);
 }
 
@@ -1608,9 +1615,9 @@ static bool adc_internal(FAR struct stm32_dev_s * priv, uint32_t *adc_ccr)
                     break;
                 }
             }
-
         }
     }
+
   return internal;
 }
 
@@ -1786,7 +1793,7 @@ static int adc_ioctl(FAR struct adc_dev_s *dev, int cmd, unsigned long arg)
 
           /* Set the watchdog threshold register */
 
-          regval= ((arg << ADC_LTR1_LT_SHIFT) & ADC_LTR1_LT_MASK);
+          regval = ((arg << ADC_LTR1_LT_SHIFT) & ADC_LTR1_LT_MASK);
           adc_putreg(priv, STM32_ADC_LTR1_OFFSET, regval);
 
           /* Ensure analog watchdog is enabled */
@@ -1941,6 +1948,7 @@ static int adc12_interrupt(int irq, FAR void *context, FAR void *arg)
  * Returned Value:
  *
  ****************************************************************************/
+
 #ifdef CONFIG_STM32H7_ADC3
 static int adc3_interrupt(int irq, FAR void *context, FAR void *arg)
 {
@@ -1994,7 +2002,8 @@ static void adc_dmaconvcallback(DMA_HANDLE handle, uint8_t isr, FAR void *arg)
 
       for (i = 0; i < priv->nchannels; i++)
         {
-          priv->cb->au_receive(dev, priv->chanlist[priv->current], priv->dmabuffer[priv->current]);
+          priv->cb->au_receive(dev, priv->chanlist[priv->current],
+                               priv->dmabuffer[priv->current]);
           priv->current++;
           if (priv->current >= priv->nchannels)
             {
diff --git a/arch/arm/src/stm32h7/stm32_ethernet.c b/arch/arm/src/stm32h7/stm32_ethernet.c
index a3d1974..c8035dd 100644
--- a/arch/arm/src/stm32h7/stm32_ethernet.c
+++ b/arch/arm/src/stm32h7/stm32_ethernet.c
@@ -786,6 +786,7 @@ static int  stm32_ethconfig(struct stm32_ethmac_s *priv);
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
+
 /****************************************************************************
  * Name: stm32_getreg
  *
@@ -834,14 +835,14 @@ static uint32_t stm32_getreg(uint32_t addr)
 
   else
     {
-        /* Did we print "..." for the previous value? */
+      /* Did we print "..." for the previous value? */
 
-        if (count > 3)
-          {
-            /* Yes.. then show how many times the value repeated */
+      if (count > 3)
+        {
+          /* Yes.. then show how many times the value repeated */
 
-            ninfo("[repeats %d more times]\n", count - 3);
-          }
+          ninfo("[repeats %d more times]\n", count - 3);
+        }
 
       /* Save the new address, value, and count */
 
@@ -1038,6 +1039,7 @@ static inline bool stm32_isfreebuffer(struct stm32_ethmac_s *priv)
  *   pointer to the next tx descriptor for the current interface
  *
  ****************************************************************************/
+
 static struct eth_desc_s *stm32_get_next_txdesc(struct stm32_ethmac_s *priv,
                                                 struct eth_desc_s * curr)
 {
@@ -1081,8 +1083,8 @@ static int stm32_transmit(struct stm32_ethmac_s *priv)
   struct eth_desc_s *txdesc;
   struct eth_desc_s *txfirst;
 
-  /* The internal (optimal) network buffer size may be configured to be larger
-   * than the Ethernet buffer size.
+  /* The internal (optimal) network buffer size may be configured to be
+   * larger than the Ethernet buffer size.
    */
 
 #if OPTIMAL_ETH_BUFSIZE > ALIGNED_BUFSIZE
@@ -1116,24 +1118,24 @@ static int stm32_transmit(struct stm32_ethmac_s *priv)
 
 #if OPTIMAL_ETH_BUFSIZE > ALIGNED_BUFSIZE
   if (priv->dev.d_len > ALIGNED_BUFSIZE)
-  {
-    /* Yes... how many buffers will be need to send the packet? */
+    {
+      /* Yes... how many buffers will be need to send the packet? */
 
-    bufcount = (priv->dev.d_len + (ALIGNED_BUFSIZE - 1)) / ALIGNED_BUFSIZE;
-    lastsize = priv->dev.d_len - (bufcount - 1) * ALIGNED_BUFSIZE;
+      bufcount = (priv->dev.d_len + (ALIGNED_BUFSIZE - 1)) / ALIGNED_BUFSIZE;
+      lastsize = priv->dev.d_len - (bufcount - 1) * ALIGNED_BUFSIZE;
 
-    ninfo("bufcount: %d lastsize: %d\n", bufcount, lastsize);
+      ninfo("bufcount: %d lastsize: %d\n", bufcount, lastsize);
 
-    /* Set the first segment bit in the first TX descriptor */
+      /* Set the first segment bit in the first TX descriptor */
 
-    txdesc->des3 = ETH_TDES3_RD_FD;
+      txdesc->des3 = ETH_TDES3_RD_FD;
 
-    /* Set up all but the last TX descriptor */
+      /* Set up all but the last TX descriptor */
 
-    buffer = priv->dev.d_buf;
+      buffer = priv->dev.d_buf;
 
-    for (i = 0; i < bufcount; i++)
-      {
+      for (i = 0; i < bufcount; i++)
+        {
           /* This could be a normal event but the design does not handle it */
 
           DEBUGASSERT((txdesc->des3 & ETH_TDES3_RD_OWN) == 0);
@@ -1541,6 +1543,7 @@ static void stm32_disableint(struct stm32_ethmac_s *priv, uint32_t ierbit)
  *   pointer to the next rx descriptor for the current interface
  *
  ****************************************************************************/
+
 static struct eth_desc_s *stm32_get_next_rxdesc(struct stm32_ethmac_s *priv,
                                                 struct eth_desc_s * curr)
 {
@@ -2887,7 +2890,6 @@ static int stm32_rmmac(struct net_driver_s *dev, const uint8_t *mac)
 
 static void stm32_txdescinit(struct stm32_ethmac_s *priv,
                              union stm32_desc_u *txtable)
-
 {
   struct eth_desc_s *txdesc;
   int i;
@@ -4286,18 +4288,18 @@ static int stm32_ethconfig(struct stm32_ethmac_s *priv)
   ninfo("Initialize the PHY\n");
   ret = stm32_phyinit(priv);
   if (ret < 0)
-  {
-    return ret;
-  }
+    {
+      return ret;
+    }
 
   /* Initialize the MAC and DMA */
 
   ninfo("Initialize the MAC and DMA\n");
   ret = stm32_macconfig(priv);
   if (ret < 0)
-  {
-    return ret;
-  }
+    {
+      return ret;
+    }
 
   /* Enable normal MAC operation */
 
@@ -4372,11 +4374,11 @@ static inline int stm32_ethinitialize(int intf)
   /* Attach the IRQ to the driver */
 
   if (irq_attach(STM32_IRQ_ETH, stm32_interrupt, NULL))
-  {
-    /* We could not attach the ISR to the interrupt */
+    {
+      /* We could not attach the ISR to the interrupt */
 
-    return -EAGAIN;
-  }
+      return -EAGAIN;
+    }
 
   /* Put the interface in the down state. */
 
diff --git a/arch/arm/src/stm32h7/stm32_ethernet.h b/arch/arm/src/stm32h7/stm32_ethernet.h
index 92da890..fc17197 100644
--- a/arch/arm/src/stm32h7/stm32_ethernet.h
+++ b/arch/arm/src/stm32h7/stm32_ethernet.h
@@ -48,7 +48,7 @@
 #ifndef __ASSEMBLY__
 
 /****************************************************************************
- * Public Functions
+ * Public Function Prototypes
  ****************************************************************************/
 
 #undef EXTERN
@@ -103,7 +103,7 @@ int stm32_ethinitialize(int intf);
  *
  * Assumptions:
  *
- ***************************************************************************/
+ ****************************************************************************/
 
 #ifdef CONFIG_STM32H7_PHYINIT
 int stm32_phy_boardinitialize(int intf);
diff --git a/arch/arm/src/stm32h7/stm32_flash.c b/arch/arm/src/stm32h7/stm32_flash.c
index 0881eac..c7dc127 100644
--- a/arch/arm/src/stm32h7/stm32_flash.c
+++ b/arch/arm/src/stm32h7/stm32_flash.c
@@ -1,5 +1,5 @@
 /****************************************************************************
- * arch/arm/src/stm32h7/stm32h7_flash.c
+ * arch/arm/src/stm32h7/stm32_flash.c
  *
  *   Copyright (C) 2019 Gregory Nutt. All rights reserved.
  *   Authors: Gregory Nutt <gn...@nuttx.org>
@@ -76,8 +76,8 @@
 /* Flash size is known from the chip selection:
  *
  *   When CONFIG_STM32H7_FLASH_OVERRIDE_DEFAULT is set the
- *   CONFIG_STM32H7_FLASH_CONFIG_x selects the default FLASH size based on the
- *   chip part number. This value can be overridden with
+ *   CONFIG_STM32H7_FLASH_CONFIG_x selects the default FLASH size based on
+ *   the chip part number. This value can be overridden with
  *   CONFIG_STM32H7_FLASH_OVERRIDE_x
  *
  *   Parts STM32H74xxE have 512Kb of FLASH
@@ -147,7 +147,7 @@
 
 #define PROGMEM_NBLOCKS STM32_FLASH_NPAGES
 
-/*****************************************************************************
+/****************************************************************************
  * Private Types
  ****************************************************************************/
 
@@ -184,13 +184,13 @@ static struct stm32h7_flash_priv_s stm32h7_flash_bank2_priv =
  * Private Functions
  ****************************************************************************/
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_getreg32
  *
  * Description:
  *   Get a 32-bit register value by offset
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static inline uint32_t stm32h7_flash_getreg32(FAR struct stm32h7_flash_priv_s
                                             *priv, uint32_t offset)
@@ -198,7 +198,7 @@ static inline uint32_t stm32h7_flash_getreg32(FAR struct stm32h7_flash_priv_s
   return getreg32(priv->ifbase + offset);
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_putreg32
  *
  * Description:
@@ -213,13 +213,13 @@ static inline void stm32h7_flash_putreg32(FAR struct stm32h7_flash_priv_s
   putreg32(value, priv->ifbase + offset);
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_modifyreg32
  *
  * Description:
  *   Modify a 32-bit register value by offset
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static inline void stm32h7_flash_modifyreg32(FAR struct stm32h7_flash_priv_s
                                              *priv, uint32_t offset,
@@ -229,26 +229,26 @@ static inline void stm32h7_flash_modifyreg32(FAR struct stm32h7_flash_priv_s
   modifyreg32(priv->ifbase + offset, clearbits, setbits);
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_sem_lock
  *
  * Description:
  *   Take the Bank exclusive access semaphore
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static void stm32h7_flash_sem_lock(FAR struct stm32h7_flash_priv_s *priv)
 {
   nxsem_wait_uninterruptible(&priv->sem);
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_sem_unlock
  *
  * Description:
  *   Release the Bank exclusive access semaphore
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static inline void stm32h7_flash_sem_unlock(FAR struct stm32h7_flash_priv_s
                                             *priv)
@@ -256,13 +256,13 @@ static inline void stm32h7_flash_sem_unlock(FAR struct stm32h7_flash_priv_s
   nxsem_post(&priv->sem);
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_unlock_flash
  *
  * Description:
  *   Unlock the Bank
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static void stm32h7_unlock_flash(FAR struct stm32h7_flash_priv_s *priv)
 {
@@ -279,38 +279,39 @@ static void stm32h7_unlock_flash(FAR struct stm32h7_flash_priv_s *priv)
     }
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_lock_flash
  *
  * Description:
  *   Lock the Bank
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static void stm32h7_lock_flash(FAR struct stm32h7_flash_priv_s *priv)
 {
   stm32h7_flash_modifyreg32(priv, STM32_FLASH_CR1_OFFSET, 0, FLASH_CR_LOCK);
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_size
  *
  * Description:
  *   Returns the size in bytes of FLASH
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static inline uint32_t stm32h7_flash_size(FAR struct stm32h7_flash_priv_s *priv)
 {
   return FLASH_SECTOR_SIZE * PROGMEM_NBLOCKS;
 }
-/*****************************************************************************
+
+/****************************************************************************
  * Name: stm32h7_flash_bank
  *
  * Description:
  *   Returns the priv pointer to the correct bank
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static inline
 FAR struct stm32h7_flash_priv_s * stm32h7_flash_bank(size_t address)
@@ -320,6 +321,7 @@ FAR struct stm32h7_flash_priv_s * stm32h7_flash_bank(size_t address)
     {
       return NULL;
     }
+
 #if STM32_FLASH_NPAGES > 1
   if (address >= stm32h7_flash_bank2_priv.base)
     {
@@ -330,13 +332,13 @@ FAR struct stm32h7_flash_priv_s * stm32h7_flash_bank(size_t address)
   return priv;
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_unlock_flashopt
  *
  * Description:
  *   Unlock the flash option bytes
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static void stm32h7_unlock_flashopt(FAR struct stm32h7_flash_priv_s *priv)
 {
@@ -353,26 +355,26 @@ static void stm32h7_unlock_flashopt(FAR struct stm32h7_flash_priv_s *priv)
     }
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_lock_flashopt
  *
  * Description:
  *   Lock the flash option bytes
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static void stm32h7_lock_flashopt(FAR struct stm32h7_flash_priv_s *priv)
 {
   stm32h7_flash_modifyreg32(priv, STM32_FLASH_OPTCR_OFFSET, 0, FLASH_OPTCR_OPTLOCK);
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_save_flashopt
  *
  * Description:
  *   Save the flash option bytes to non-volatile storage.
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 static void stm32h7_save_flashopt(FAR struct stm32h7_flash_priv_s *priv)
 {
@@ -386,13 +388,18 @@ static void stm32h7_save_flashopt(FAR struct stm32h7_flash_priv_s *priv)
     }
 
   /* Can only write flash options if the option control reg is unlocked */
-  if (!(stm32h7_flash_getreg32(priv, STM32_FLASH_OPTCR_OFFSET) & FLASH_OPTCR_OPTLOCK))
+
+  if (!(stm32h7_flash_getreg32(priv, STM32_FLASH_OPTCR_OFFSET) &
+                               FLASH_OPTCR_OPTLOCK))
     {
-      stm32h7_flash_modifyreg32(priv, STM32_FLASH_OPTCR_OFFSET, 0, FLASH_OPTCR_OPTSTRT);
+      stm32h7_flash_modifyreg32(priv, STM32_FLASH_OPTCR_OFFSET, 0,
+                                FLASH_OPTCR_OPTSTRT);
     }
 
   /* Wait for the update to complete */
-  while (stm32h7_flash_getreg32(priv, STM32_FLASH_OPTSR_CUR_OFFSET) & FLASH_OPTSR_BUSYV)
+
+  while (stm32h7_flash_getreg32(priv, STM32_FLASH_OPTSR_CUR_OFFSET) &
+                                      FLASH_OPTSR_BUSYV)
     {
     }
 }
@@ -401,13 +408,13 @@ static void stm32h7_save_flashopt(FAR struct stm32h7_flash_priv_s *priv)
  * Public Functions
  ****************************************************************************/
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_unlock
  *
  * Description:
  *   Unlocks a bank
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 int stm32h7_flash_unlock(size_t addr)
 {
@@ -425,13 +432,13 @@ int stm32h7_flash_unlock(size_t addr)
   return rv;
 }
 
-/*****************************************************************************
+/****************************************************************************
  * Name: stm32h7_flash_lock
  *
  * Description:
  *   Locks a bank
  *
- *****************************************************************************/
+ ****************************************************************************/
 
 int stm32h7_flash_lock(size_t addr)
 {
@@ -506,6 +513,7 @@ uint32_t stm32h7_flash_getopt(void)
     {
       return stm32h7_flash_getreg32(priv, STM32_FLASH_OPTSR_CUR_OFFSET);
     }
+
   return 0;
 }
 
@@ -526,7 +534,7 @@ void stm32h7_flash_optmodify(uint32_t clear, uint32_t set)
     stm32h7_unlock_flashopt(priv);
     stm32h7_flash_modifyreg32(priv, STM32_FLASH_OPTSR_PRG_OFFSET, clear, set);
     stm32h7_save_flashopt(priv);
-  }
+    }
 }
 
 /****************************************************************************
@@ -566,6 +574,7 @@ ssize_t up_progmem_getpage(size_t addr)
     {
       return -EFAULT;
     }
+
   return  priv->stblock + ((addr - priv->base) / FLASH_SECTOR_SIZE);
 }
 
@@ -811,6 +820,7 @@ ssize_t up_progmem_write(size_t addr, const void *buf, size_t count)
             }
         }
     }
+
   stm32h7_flash_modifyreg32(priv, STM32_FLASH_CR1_OFFSET, FLASH_CR_PG, 0);
   stm32h7_flash_sem_unlock(priv);
   return written;
diff --git a/arch/arm/src/stm32h7/stm32_flash.h b/arch/arm/src/stm32h7/stm32_flash.h
index ca2696a..abc4301 100644
--- a/arch/arm/src/stm32h7/stm32_flash.h
+++ b/arch/arm/src/stm32h7/stm32_flash.h
@@ -1,5 +1,5 @@
 /****************************************************************************
- * arch/arm/src/stm32h7/stm32_fflash.h
+ * arch/arm/src/stm32h7/stm32_flash.h
  *
  *   Copyright (C) 2020 Gregory Nutt. All rights reserved.
  *   Author: Joshua Lange <jl...@2g-eng.com>
@@ -46,7 +46,7 @@
 #include "hardware/stm32_flash.h"
 
 /****************************************************************************
- * Public Functions
+ * Public Function Prototypes
  ****************************************************************************/
 
 #ifndef __ASSEMBLY__
diff --git a/arch/arm/src/stm32h7/stm32_iwdg.c b/arch/arm/src/stm32h7/stm32_iwdg.c
index 184592a..12d95d4 100644
--- a/arch/arm/src/stm32h7/stm32_iwdg.c
+++ b/arch/arm/src/stm32h7/stm32_iwdg.c
@@ -1,7 +1,7 @@
 /****************************************************************************
  * arch/arm/src/stm32h7/stm32_iwdg.c
  *
- *   Copyright (C) 2012, 2016 Gregory Nutt. All rights reserved.
+ *   Copyright (C) 2012, 2016, 2020 Gregory Nutt. All rights reserved.
  *   Author: Gregory Nutt <gn...@nuttx.org>
  *
  * Redistribution and use in source and binary forms, with or without
@@ -58,7 +58,9 @@
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
+
 /* Clocking *****************************************************************/
+
 /* The minimum frequency of the IWDG clock is:
  *
  *  Fmin = Flsi / 256
@@ -111,6 +113,7 @@
 /****************************************************************************
  * Private Types
  ****************************************************************************/
+
 /* This structure provides the private representation of the "lower-half"
  * driver state structure.  This structure must be cast-compatible with the
  * well-known watchdog_lowerhalf_s structure.
@@ -130,6 +133,7 @@ struct stm32_lowerhalf_s
 /****************************************************************************
  * Private Function Prototypes
  ****************************************************************************/
+
 /* Register operations ******************************************************/
 
 #ifdef CONFIG_STM32H7_IWDG_REGDEBUG
@@ -155,6 +159,7 @@ static int      stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
 /****************************************************************************
  * Private Data
  ****************************************************************************/
+
 /* "Lower half" driver methods */
 
 static const struct watchdog_ops_s g_wdgops =
@@ -195,8 +200,8 @@ static uint16_t stm32_getreg(uint32_t addr)
 
   uint16_t val = getreg16(addr);
 
-  /* Is this the same value that we read from the same register last time?  Are
-   * we polling the register?  If so, suppress some of the output.
+  /* Is this the same value that we read from the same register last time?
+   * Are we polling the register?  If so, suppress some of the output.
    */
 
   if (addr == prevaddr && val == preval)
@@ -222,7 +227,7 @@ static uint16_t stm32_getreg(uint32_t addr)
         {
           /* Yes.. then show how many times the value repeated */
 
-          wdinfo("[repeats %d more times]\n", count-3);
+          wdinfo("[repeats %d more times]\n", count - 3);
         }
 
       /* Save the new address, value, and count */
@@ -268,8 +273,8 @@ static void stm32_putreg(uint16_t val, uint32_t addr)
  *   that can only be done one time.
  *
  * Input Parameters:
- *   priv   - A pointer the internal representation of the "lower-half"
- *             driver state structure.
+ *   priv   - a pointer to the internal representation of the
+ *            "lower-half" driver state structure.
  *
  ****************************************************************************/
 
@@ -311,8 +316,8 @@ static inline void stm32_setprescaler(FAR struct stm32_lowerhalf_s *priv)
  *   Start the watchdog timer, resetting the time to the current timeout,
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   lower - a pointer to the publicly visible representation of the
+ *   "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -331,10 +336,11 @@ static int stm32_start(FAR struct watchdog_lowerhalf_s *lower)
 
   if (!priv->started)
     {
-      /* REVISIT:  It appears that you can only setup the prescaler and reload
-       * registers once.  After that, the SR register's PVU and RVU bits never go
-       * to zero.  So we defer setting up these registers until the watchdog
-       * is started, then refuse any further attempts to change timeout.
+      /* REVISIT:  It appears that you can only setup the prescaler and
+       * reload registers once.  After that, the SR register's PVU and RVU
+       * bits never go to zero.  So we defer setting up these registers until
+       * the watchdog is started, then refuse any further attempts to change
+       * timeout.
        */
 
       /* Set up prescaler and reload value for the selected timeout before
@@ -346,8 +352,8 @@ static int stm32_start(FAR struct watchdog_lowerhalf_s *lower)
 #endif
 
       /* Enable IWDG (the LSI oscillator will be enabled by hardware).  NOTE:
-       * If the "Hardware watchdog" feature is enabled through the device option
-       * bits, the watchdog is automatically enabled at power-on.
+       * If the "Hardware watchdog" feature is enabled through the device
+       * option bits, the watchdog is automatically enabled at power-on.
        */
 
       flags           = enter_critical_section();
@@ -367,8 +373,8 @@ static int stm32_start(FAR struct watchdog_lowerhalf_s *lower)
  *   Stop the watchdog timer
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   lower - a pointer to the publicly visible representation of the
+ *           "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -392,8 +398,8 @@ static int stm32_stop(FAR struct watchdog_lowerhalf_s *lower)
  *   the watchdog timer or "petting the dog".
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   lower - a pointer to the publicly visible representation of the
+ *   "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -424,8 +430,8 @@ static int stm32_keepalive(FAR struct watchdog_lowerhalf_s *lower)
  *   Get the current watchdog timer status
  *
  * Input Parameters:
- *   lower  - A pointer the publicly visible representation of the "lower-half"
- *            driver state structure.
+ *   lower  - a pointer to the publicly visible representation of the
+ *            "lower-half" driver state structure.
  *   status - The location to return the watchdog status information.
  *
  * Returned Value:
@@ -483,8 +489,8 @@ static int stm32_getstatus(FAR struct watchdog_lowerhalf_s *lower,
  *   Set a new timeout value (and reset the watchdog timer)
  *
  * Input Parameters:
- *   lower   - A pointer the publicly visible representation of the "lower-half"
- *             driver state structure.
+ *   lower   - A pointer to the publicly visible representation of the
+ *             "lower-half" driver state structure.
  *   timeout - The new timeout value in milliseconds.
  *
  * Returned Value:
@@ -604,8 +610,8 @@ static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
    */
 
 #ifndef CONFIG_STM32H7_IWDG_ONETIMESETUP
-  /* If CONFIG_STM32H7_IWDG_DEFERREDSETUP is selected, then perform the register
-   * configuration only if the timer has been started.
+  /* If CONFIG_STM32H7_IWDG_DEFERREDSETUP is selected, then perform the
+   * register configuration only if the timer has been started.
    */
 
 #ifdef CONFIG_STM32H7_IWDG_DEFERREDSETUP
@@ -629,8 +635,8 @@ static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
  * Name: stm32_iwdginitialize
  *
  * Description:
- *   Initialize the IWDG watchdog timer.  The watchdog timer is initialized and
- *   registers as 'devpath'.  The initial state of the watchdog timer is
+ *   Initialize the IWDG watchdog timer.  The watchdog timer is initialized
+ *   and registers as 'devpath'.  The initial state of the watchdog timer is
  *   disabled.
  *
  * Input Parameters:
@@ -674,7 +680,8 @@ void stm32_iwdginitialize(FAR const char *devpath, uint32_t lsifreq)
    * device option bits, the watchdog is automatically enabled at power-on.
    */
 
-  stm32_settimeout((FAR struct watchdog_lowerhalf_s *)priv, CONFIG_STM32H7_IWDG_DEFTIMOUT);
+  stm32_settimeout((FAR struct watchdog_lowerhalf_s *)priv,
+                   CONFIG_STM32H7_IWDG_DEFTIMOUT);
 
   /* Register the watchdog driver as /dev/watchdog0 */
 
diff --git a/arch/arm/src/stm32h7/stm32_pm.h b/arch/arm/src/stm32h7/stm32_pm.h
index 5339ffe..bcbc899 100644
--- a/arch/arm/src/stm32h7/stm32_pm.h
+++ b/arch/arm/src/stm32h7/stm32_pm.h
@@ -1,4 +1,4 @@
-/************************************************************************************
+/****************************************************************************
  * arch/arm/src/stm32h7/stm32_pm.h
  *
  *   Copyright (C) 2018 Haltian Ltd. All rights reserved.
@@ -31,7 +31,7 @@
  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  * POSSIBILITY OF SUCH DAMAGE.
  *
- ************************************************************************************/
+ ****************************************************************************/
 
 #ifndef __ARCH_ARM_SRC_STM32H7_STM32_PM_H
 #define __ARCH_ARM_SRC_STM32H7_STM32_PM_H
@@ -68,8 +68,8 @@ extern "C"
  *
  * Input Parameters:
  *   lpds - true: To further reduce power consumption in Stop mode, put the
- *          internal voltage regulator in low-power under-drive mode using the
- *          LPDS and LPUDS bits of the Power control register (PWR_CR1).
+ *          internal voltage regulator in low-power under-drive mode using
+ *          the LPDS and LPUDS bits of the Power control register (PWR_CR1).
  *
  * Returned Value:
  *   None
@@ -104,8 +104,8 @@ void stm32_pmstandby(void);
  *   sleeponexit - true:  SLEEPONEXIT bit is set when the WFI instruction is
  *                        executed, the MCU enters Sleep mode as soon as it
  *                        exits the lowest priority ISR.
- *               - false: SLEEPONEXIT bit is cleared, the MCU enters Sleep mode
- *                        as soon as WFI or WFE instruction is executed.
+ *               - false: SLEEPONEXIT bit is cleared, the MCU enters Sleep
+ *                        mode as soon as WFI or WFE instruction is executed.
  * Returned Value:
  *   None
  *
diff --git a/arch/arm/src/stm32h7/stm32_pminitialize.c b/arch/arm/src/stm32h7/stm32_pminitialize.c
index ffcd5d0..14914b4 100644
--- a/arch/arm/src/stm32h7/stm32_pminitialize.c
+++ b/arch/arm/src/stm32h7/stm32_pminitialize.c
@@ -1,7 +1,7 @@
 /****************************************************************************
  * arch/arm/src/stm32h7/stm32_pminitialize.c
  *
- *   Copyright (C) 2012, 2017 Gregory Nutt. All rights reserved.
+ *   Copyright (C) 2012, 2017, 2020 Gregory Nutt. All rights reserved.
  *   Author: Gregory Nutt <gn...@nuttx.org>
  *
  * Redistribution and use in source and binary forms, with or without
diff --git a/arch/arm/src/stm32h7/stm32_pmsleep.c b/arch/arm/src/stm32h7/stm32_pmsleep.c
index b7c92e4..d77da01 100644
--- a/arch/arm/src/stm32h7/stm32_pmsleep.c
+++ b/arch/arm/src/stm32h7/stm32_pmsleep.c
@@ -1,7 +1,7 @@
 /****************************************************************************
  * arch/arm/src/stm32h7/stm32_pmsleep.c
  *
- *   Copyright (C) 2012, 2017 Gregory Nutt. All rights reserved.
+ *   Copyright (C) 2012, 2017, 2020 Gregory Nutt. All rights reserved.
  *   Authors: Gregory Nutt <gn...@nuttx.org>
  *            Diego Sanchez <ds...@nx-engineering.com>
  *
@@ -61,8 +61,8 @@
  *   sleeponexit - true:  SLEEPONEXIT bit is set when the WFI instruction is
  *                        executed, the MCU enters Sleep mode as soon as it
  *                        exits the lowest priority ISR.
- *               - false: SLEEPONEXIT bit is cleared, the MCU enters Sleep mode
- *                        as soon as WFI or WFE instruction is executed.
+ *               - false: SLEEPONEXIT bit is cleared, the MCU enters Sleep
+ *                        mode as soon as WFI or WFE instruction is executed.
  * Returned Value:
  *   None
  *
diff --git a/arch/arm/src/stm32h7/stm32_pmstandby.c b/arch/arm/src/stm32h7/stm32_pmstandby.c
index 2486e1c..bddcfc1 100644
--- a/arch/arm/src/stm32h7/stm32_pmstandby.c
+++ b/arch/arm/src/stm32h7/stm32_pmstandby.c
@@ -80,8 +80,9 @@ void stm32_pmstandby(void)
 
   modifyreg32(STM32_RCC_CSR, 0, RCC_RSR_RMVF);
 
-  /* Set the domain Power Down Deep Sleep (PDDS) bits in the power control register.
-   * so that D1, D2, and D3 will go into the DStop state. */
+  /* Set the domain Power Down Deep Sleep (PDDS) bits in the power control
+   * register so that D1, D2, and D3 will go into the DStop state.
+   */
 
   modifyreg32(STM32_PWR_CPUCR, 0, STM32_PWR_CPUCR_PDDS_D1 |
                                   STM32_PWR_CPUCR_PDDS_D2 |
diff --git a/arch/arm/src/stm32h7/stm32_pmstop.c b/arch/arm/src/stm32h7/stm32_pmstop.c
index 6159e8c..5c6f005 100644
--- a/arch/arm/src/stm32h7/stm32_pmstop.c
+++ b/arch/arm/src/stm32h7/stm32_pmstop.c
@@ -58,8 +58,8 @@
  *
  * Input Parameters:
  *   lpds - true: To further reduce power consumption in Stop mode, put the
- *          internal voltage regulator in low-power under-drive mode using the
- *          LPDS and LPUDS bits of the Power control register (PWR_CR1).
+ *          internal voltage regulator in low-power under-drive mode using
+ *          the LPDS and LPUDS bits of the Power control register (PWR_CR1).
  *
  * Returned Value:
  *   None
@@ -70,7 +70,8 @@ void stm32_pmstop(bool lpds)
 {
   uint32_t regval;
 
-  /* Clear the Low Power Deep Sleep (LPDS) bit in the CPU power control register.
+  /* Clear the Low Power Deep Sleep (LPDS) bit in the CPU power control
+   * register.
    */
 
   regval  = getreg32(STM32_PWR_CR1);
@@ -94,7 +95,8 @@ void stm32_pmstop(bool lpds)
   /* Clear the domain standby bits so D1, D2 and D3 remain in DStop mode */
 
   regval  = getreg32(STM32_PWR_CPUCR);
-  regval &= ~(STM32_PWR_CPUCR_PDDS_D1 | STM32_PWR_CPUCR_PDDS_D2 | STM32_PWR_CPUCR_PDDS_D3);
+  regval &= ~(STM32_PWR_CPUCR_PDDS_D1 | STM32_PWR_CPUCR_PDDS_D2 |
+              STM32_PWR_CPUCR_PDDS_D3);
   putreg32(regval, STM32_PWR_CPUCR);
 
   /* Set SLEEPDEEP bit of Cortex System Control Register */
diff --git a/arch/arm/src/stm32h7/stm32_pwr.c b/arch/arm/src/stm32h7/stm32_pwr.c
index 0ae5051..e087b4f 100644
--- a/arch/arm/src/stm32h7/stm32_pwr.c
+++ b/arch/arm/src/stm32h7/stm32_pwr.c
@@ -270,12 +270,13 @@ void stm32_pwr_disablepvd(void)
  * Description:
  *   Enables the Backup regulator, the Backup regulator (used to maintain backup
  *   SRAM content in Standby and VBAT modes) is enabled. If BRE is reset, the backup
- *   regulator is switched off. The backup SRAM can still be used but its content will
- *   be lost in the Standby and VBAT modes. Once set, the application must wait that
- *   the Backup Regulator Ready flag (BRR) is set to indicate that the data written
- *   into the RAM will be maintained in the Standby and VBAT modes.
+ *   regulator is switched off. The backup SRAM can still be used but its content
+ *   will be lost in the Standby and VBAT modes. Once set, the application must wait
+ *   that the Backup Regulator Ready flag (BRR) is set to indicate that the data
+ *   written into the RAM will be maintained in the Standby and VBAT modes.
  *
- *   This function needs to be called after stm32_pwr_enablebkp(true) has been called.
+ *   This function needs to be called after stm32_pwr_enablebkp(true) has been
+ *   called.
  *
  * Input Parameters:
  *   region - state to set it to
@@ -367,7 +368,9 @@ void stm32_pwr_configurewkup(uint32_t pin, bool en, bool rising, uint32_t pull)
     {
       regval     |= STM32_PWR_WKUPP(pin);
     }
+
   /* Set to the no pull-up state by default*/
+
   regval &= ~ (STM32_PWR_WKUPPUPD_MASK << STM32_PWR_WKUPPUPD_SHIFT(pin));
 
   if (pull == GPIO_PULLUP)
@@ -394,12 +397,14 @@ void stm32_pwr_configurewkup(uint32_t pin, bool en, bool rising, uint32_t pull)
  *
  * Input Parameters:
  *   enable    - Enables the charge resistor if true, disables it if false
- *   resistor  - Sets charge resistor to 1.5 KOhm if true, sets it to 5 KOhm if false.
+ *   resistor  - Sets charge resistor to 1.5 KOhm if true,
+ *               sets it to 5 KOhm if false.
  *
  * Returned Value:
  *   None
  *
  ************************************************************************************/
+
 void stm32_pwr_setvbatcharge(bool enable, bool resistor)
 {
   irqstate_t flags;
diff --git a/arch/arm/src/stm32h7/stm32_pwr.h b/arch/arm/src/stm32h7/stm32_pwr.h
index 5b753e6..eb4d614 100644
--- a/arch/arm/src/stm32h7/stm32_pwr.h
+++ b/arch/arm/src/stm32h7/stm32_pwr.h
@@ -63,7 +63,7 @@ extern "C"
 #endif
 
 /************************************************************************************
- * Public Functions
+ * Public Function Prototypes
  ************************************************************************************/
 
 /************************************************************************************
@@ -110,10 +110,13 @@ void stm32_pwr_enablebkp(bool writable);
  * Description:
  *   Enables the Backup regulator, the Backup regulator (used to maintain backup
  *   SRAM content in Standby and VBAT modes) is enabled. If BRE is reset, the backup
- *   regulator is switched off. The backup SRAM can still be used but its content will
- *   be lost in the Standby and VBAT modes. Once set, the application must wait that
- *   the Backup Regulator Ready flag (BRR) is set to indicate that the data written
- *   into the RAM will be maintained in the Standby and VBAT modes.
+ *   regulator is switched off. The backup SRAM can still be used but its content
+ *   will be lost in the Standby and VBAT modes. Once set, the application must wait
+ *   that the Backup Regulator Ready flag (BRR) is set to indicate that the data
+ *   written into the RAM will be maintained in the Standby and VBAT modes.
+ *
+ *   This function needs to be called after stm32_pwr_enablebkp(true) has been
+ *   called.
  *
  * Input Parameters:
  *   region - state to set it to
@@ -158,12 +161,14 @@ void stm32_pwr_configurewkup(uint32_t pin, bool en, bool rising, uint32_t pull);
  *
  * Input Parameters:
  *   enable    - Enables the charge resistor if true, disables it if false
- *   resistor  - Sets charge resistor to 1.5 KOhm if true, sets it to 5 KOhm if false.
+ *   resistor  - Sets charge resistor to 1.5 KOhm if true,
+ *               sets it to 5 KOhm if false.
  *
  * Returned Value:
  *   None
  *
  ************************************************************************************/
+
 void stm32_pwr_setvbatcharge(bool enable, bool resistor);
 
 #undef EXTERN
diff --git a/arch/arm/src/stm32h7/stm32_wdg.h b/arch/arm/src/stm32h7/stm32_wdg.h
index 06a0011..290d39f 100644
--- a/arch/arm/src/stm32h7/stm32_wdg.h
+++ b/arch/arm/src/stm32h7/stm32_wdg.h
@@ -1,7 +1,7 @@
 /****************************************************************************
  * arch/arm/src/stm32h7/stm32_wdg.h
  *
- *   Copyright (C) 2012, 2015 Gregory Nutt. All rights reserved.
+ *   Copyright (C) 2012, 2015, 2020 Gregory Nutt. All rights reserved.
  *   Author: Gregory Nutt <gn...@nuttx.org>
  *
  * Redistribution and use in source and binary forms, with or without
@@ -63,7 +63,7 @@ extern "C"
 #endif
 
 /****************************************************************************
- * Public Functions
+ * Public Function Prototypes
  ****************************************************************************/
 
 /****************************************************************************
@@ -71,7 +71,7 @@ extern "C"
  *
  * Description:
  *   Initialize the IWDG watchdog time.  The watchdog timer is initialized
- *   and registers as 'devpath.  The initial state of the watchdog time is
+ *   and registers as 'devpath'.  The initial state of the watchdog time is
  *   disabled.
  *
  * Input Parameters:
@@ -92,8 +92,8 @@ void stm32_iwdginitialize(FAR const char *devpath, uint32_t lsifreq);
  * Name: stm32_wwdginitialize
  *
  * Description:
- *   Initialize the WWDG watchdog time.  The watchdog timer is initializeed and
- *   registers as 'devpath.  The initial state of the watchdog time is
+ *   Initialize the WWDG watchdog time.  The watchdog timer is initialized
+ *   and registers as 'devpath'.  The initial state of the watchdog time is
  *   disabled.
  *
  * Input Parameters:
diff --git a/arch/arm/src/stm32h7/stm32_wwdg.c b/arch/arm/src/stm32h7/stm32_wwdg.c
index c0d1083..23a9101 100644
--- a/arch/arm/src/stm32h7/stm32_wwdg.c
+++ b/arch/arm/src/stm32h7/stm32_wwdg.c
@@ -1,7 +1,7 @@
 /****************************************************************************
  * arch/arm/src/stm32h7/stm32_wwdg.c
  *
- *   Copyright (C) 2012, 2016 Gregory Nutt. All rights reserved.
+ *   Copyright (C) 2012, 2016, 2020 Gregory Nutt. All rights reserved.
  *   Author: Gregory Nutt <gn...@nuttx.org>
  *
  * Redistribution and use in source and binary forms, with or without
@@ -56,7 +56,9 @@
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
+
 /* Clocking *****************************************************************/
+
 /* The minimum frequency of the WWDG clock is:
  *
  *  Fmin = PCLK1 / 4096 / 8
@@ -87,6 +89,7 @@
 /****************************************************************************
  * Private Types
  ****************************************************************************/
+
 /* This structure provides the private representation of the "lower-half"
  * driver state structure.  This structure must be cast-compatible with the
  * well-known watchdog_lowerhalf_s structure.
@@ -106,6 +109,7 @@ struct stm32_lowerhalf_s
 /****************************************************************************
  * Private Function Prototypes
  ****************************************************************************/
+
 /* Register operations ******************************************************/
 
 #ifdef CONFIG_STM32H7_WWDG_REGDEBUG
@@ -139,6 +143,7 @@ static int      stm32_ioctl(FAR struct watchdog_lowerhalf_s *lower, int cmd,
 /****************************************************************************
  * Private Data
  ****************************************************************************/
+
 /* "Lower half" driver methods */
 
 static const struct watchdog_ops_s g_wdgops =
@@ -179,8 +184,8 @@ static uint16_t stm32_getreg(uint32_t addr)
 
   uint16_t val = getreg16(addr);
 
-  /* Is this the same value that we read from the same registe last time?  Are
-   * we polling the register?  If so, suppress some of the output.
+  /* Is this the same value that we read from the same register last time?
+   * Are we polling the register?  If so, suppress some of the output.
    */
 
   if (addr == prevaddr && val == preval)
@@ -206,7 +211,7 @@ static uint16_t stm32_getreg(uint32_t addr)
         {
           /* Yes.. then show how many times the value repeated */
 
-          wdinfo("[repeats %d more times]\n", count-3);
+          wdinfo("[repeats %d more times]\n", count - 3);
         }
 
       /* Save the new address, value, and count */
@@ -325,8 +330,8 @@ static int stm32_interrupt(int irq, FAR void *context, FAR void *arg)
  *   Start the watchdog timer, resetting the time to the current timeout,
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   lower - A pointer to the publicly visible representation of the
+ *           "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -357,8 +362,8 @@ static int stm32_start(FAR struct watchdog_lowerhalf_s *lower)
  *   Stop the watchdog timer
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   lower - A pointer to the publicly visible representation of the
+ *           "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -385,14 +390,14 @@ static int stm32_stop(FAR struct watchdog_lowerhalf_s *lower)
  *   the watchdog timer or "petting the dog".
  *
  *   The application program must write in the WWDG_CR register at regular
- *   intervals during normal operation to prevent an MCU reset. This operation
- *   must occur only when the counter value is lower than the window register
- *   value. The value to be stored in the WWDG_CR register must be between
- *   0xff and 0xC0:
+ *   intervals during normal operation to prevent an MCU reset. This
+ *   operation must occur only when the counter value is lower than the
+ *   window register value. The value to be stored in the WWDG_CR register
+ *   must be between 0xff and 0xC0:
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   lower - A pointer to the publicly visible representation of the
+ *           "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -421,8 +426,8 @@ static int stm32_keepalive(FAR struct watchdog_lowerhalf_s *lower)
  *   Get the current watchdog timer status
  *
  * Input Parameters:
- *   lower  - A pointer the publicly visible representation of the "lower-half"
- *            driver state structure.
+ *   lower  - A pointer to the publicly visible representation of the
+ *            "lower-half" driver state structure.
  *   status - The location to return the watchdog status information.
  *
  * Returned Value:
@@ -477,7 +482,7 @@ static int stm32_getstatus(FAR struct watchdog_lowerhalf_s *lower,
  *   Set a new timeout value (and reset the watchdog timer)
  *
  * Input Parameters:
- *   lower   - A pointer the publicly visible representation of the
+ *   lower   - A pointer to the publicly visible representation of the
  *             "lower-half" driver state structure.
  *   timeout - The new timeout value in milliseconds.
  *
@@ -516,8 +521,8 @@ static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
    *  wdgtb is one of {1, 2, 4, or 8}
    */
 
-  /* Select the smallest prescaler that will result in a reload field value that is
-   * less than the maximum.
+  /* Select the smallest prescaler that will result in a reload field value
+   * that is less than the maximum.
    */
 
   for (wdgtb = 0; ; wdgtb++)
@@ -530,7 +535,7 @@ static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
 
       /* Get the WWDG counter frequency in Hz. */
 
-      fwwdg = (STM32_PCLK1_FREQUENCY/4096) >> wdgtb;
+      fwwdg = (STM32_PCLK1_FREQUENCY / 4096) >> wdgtb;
 
       /* The formula to calculate the timeout value is given by:
        *
@@ -594,8 +599,8 @@ static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
   regval |= (uint16_t)wdgtb << WWDG_CFR_WDGTB_SHIFT;
   stm32_putreg(regval, STM32_WWDG_CFR);
 
-  /* Reset the 7-bit window value to the maximum value.. essentially disabling
-   * the lower limit of the watchdog reset time.
+  /* Reset the 7-bit window value to the maximum value...essentially
+   * disabling the lower limit of the watchdog reset time.
    */
 
   stm32_setwindow(priv, 0x7f);
@@ -611,8 +616,8 @@ static int stm32_settimeout(FAR struct watchdog_lowerhalf_s *lower,
  *   behavior.
  *
  * Input Parameters:
- *   lower      - A pointer the publicly visible representation of the "lower-half"
- *                driver state structure.
+ *   lower      - A pointer to the publicly visible representation of the
+ *                "lower-half" driver state structure.
  *   newhandler - The new watchdog expiration function pointer.  If this
  *                function pointer is NULL, then the reset-on-expiration
  *                behavior is restored,
@@ -642,7 +647,7 @@ static xcpt_t stm32_capture(FAR struct watchdog_lowerhalf_s *lower,
 
   /* Save the new handler */
 
-   priv->handler = handler;
+  priv->handler = handler;
 
   /* Are we attaching or detaching the handler? */
 
@@ -678,8 +683,8 @@ static xcpt_t stm32_capture(FAR struct watchdog_lowerhalf_s *lower,
  *   are forwarded to the lower half driver through this method.
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   lower - A pointer to the publicly visible representation of the
+ *           "lower-half" driver state structure.
  *   cmd   - The ioctl command value
  *   arg   - The optional argument that accompanies the 'cmd'.  The
  *           interpretation of this argument depends on the particular
@@ -733,8 +738,8 @@ static int stm32_ioctl(FAR struct watchdog_lowerhalf_s *lower, int cmd,
  * Name: stm32_wwdginitialize
  *
  * Description:
- *   Initialize the WWDG watchdog timer.  The watchdog timer is initialized and
- *   registers as 'devpath'.  The initial state of the watchdog timer is
+ *   Initialize the WWDG watchdog timer.  The watchdog timer is initialized
+ *   and registers as 'devpath'.  The initial state of the watchdog timer is
  *   disabled.
  *
  * Input Parameters:
diff --git a/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c b/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c
index 536b225..b1881e4 100644
--- a/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c
+++ b/arch/arm/src/stm32h7/stm32h7x3xx_rcc.c
@@ -95,7 +95,6 @@
 #  endif
 #endif
 
-
 /* PLL are only enabled if the P,Q or R outputs are enabled. */
 
 #undef USE_PLL1
@@ -143,8 +142,8 @@ static inline void rcc_reset(void)
   putreg32(regval, STM32_RCC_CR);
 
 #if defined(CONFIG_STM32H7_AXI_SRAM_CORRUPTION_WAR)
-  /* Errata 2.2.9 Enable workaround for Reading from AXI SRAM may lead to data
-   * read corruption. See ES0392 Rev 6.
+  /* Errata 2.2.9 Enable workaround for Reading from AXI SRAM may lead to
+   * data read corruption. See ES0392 Rev 6.
    */
 
   putreg32(AXI_TARG_READ_ISS_OVERRIDE, STM32_AXI_TARG7_FN_MOD);
@@ -767,6 +766,7 @@ static void stm32_stdclockconfig(void)
         {
         }
 #endif
+
 #if defined(USE_PLL3)
       /* Wait until the PLL3 is ready */
 
@@ -776,15 +776,15 @@ static void stm32_stdclockconfig(void)
 #endif
 
       /* Ww must write the lower byte of the PWR_CR3 register is written once
-       * after POR and it shall be written before changing VOS level or ck_sys
-       * clock frequency. No limitation applies to the upper bytes.
+       * after POR and it shall be written before changing VOS level or
+       * ck_sys clock frequency. No limitation applies to the upper bytes.
        *
        * Programming data corresponding to an invalid combination of
        * LDOEN and BYPASS bits will be ignored: data will not be written,
        * the written-once mechanism will lock the register and any further
        * write access will be ignored. The default supply configuration will
-       * be kept and the ACTVOSRDY bit in PWR control status register 1 (PWR_CSR1)
-       * will go on indicating invalid voltage levels.
+       * be kept and the ACTVOSRDY bit in PWR control status register 1
+       * (PWR_CSR1) will go on indicating invalid voltage levels.
        *
        * N.B. The system shall be power cycled before writing a new value.
        */
@@ -805,6 +805,7 @@ static void stm32_stdclockconfig(void)
         }
 
       /* See Reference manual Section 5.4.1, System supply startup */
+
       while ((getreg32(STM32_PWR_CSR1) & PWR_CSR1_ACTVOSRDY) == 0)
         {
         }
@@ -817,7 +818,6 @@ static void stm32_stdclockconfig(void)
       if ((STM32_PWR_VOS_SCALE == PWR_D3CR_VOS_SCALE_1) &&
            STM32_SYSCLK_FREQUENCY > 400000000)
         {
-
           /* Enable System configuration controller clock to Enable ODEN */
 
           regval = getreg32(STM32_RCC_APB4ENR);
@@ -840,7 +840,6 @@ static void stm32_stdclockconfig(void)
       regval = FLASH_ACR_WRHIGHFREQ(BOARD_FLASH_PROGDELAY) |
                FLASH_ACR_LATENCY(BOARD_FLASH_WAITSTATES);
 
-
       putreg32(regval, STM32_FLASH_ACR);
 
       /* Select the PLL1P as system clock source */