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/08/08 20:33:34 UTC

[incubator-nuttx] branch master updated (f618de9 -> ca62cb6)

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

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


    from f618de9  Fix nxstyle warning
     new e7073df  arch: samd5e5 : Add watchdog timer drivers.
     new ca62cb6  Style fixes

The 2 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/samd5e5/hardware/sam_wdt.h            | 126 +++---
 arch/arm/src/samd5e5/sam_wdt.c                     | 464 +++++++++++++++++++++
 .../esp32_spiflash.h => arm/src/samd5e5/sam_wdt.h} |  54 ++-
 boards/arm/samd5e5/metro-m4/src/sam_bringup.c      |   8 +
 4 files changed, 554 insertions(+), 98 deletions(-)
 create mode 100644 arch/arm/src/samd5e5/sam_wdt.c
 copy arch/{xtensa/src/esp32/esp32_spiflash.h => arm/src/samd5e5/sam_wdt.h} (69%)


[incubator-nuttx] 02/02: Style fixes

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

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

commit ca62cb6b76f2c8e61c70b807aa885e0dee236ab5
Author: leomarradke <le...@falker.com.br>
AuthorDate: Tue Aug 4 19:56:39 2020 -0300

    Style fixes
---
 arch/arm/src/samd5e5/hardware/sam_wdt.h | 126 ++++++++----------
 arch/arm/src/samd5e5/sam_wdt.c          | 218 ++++++++++++--------------------
 arch/arm/src/samd5e5/sam_wdt.h          |  42 +++---
 3 files changed, 155 insertions(+), 231 deletions(-)

diff --git a/arch/arm/src/samd5e5/hardware/sam_wdt.h b/arch/arm/src/samd5e5/hardware/sam_wdt.h
index d8024f5..f6911b5 100644
--- a/arch/arm/src/samd5e5/hardware/sam_wdt.h
+++ b/arch/arm/src/samd5e5/hardware/sam_wdt.h
@@ -1,54 +1,43 @@
-/********************************************************************************************
+/****************************************************************************
  * arch/arm/src/samd5e5/hardware/sam_wdt.h
  *
- *   Copyright (C) 2018 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ *   Copyright 2020 Falker Automacao Agricola LTDA.
+ *   Author: Leomar Mateus Radke <le...@falker.com.br>
+ *   Author: Ricardo Wartchow <wa...@gmail.com>
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * 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.
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
- ********************************************************************************************/
+ ****************************************************************************/
 
 #ifndef __ARCH_ARM_SRC_SAMD5E5_HARDWARE_SAM_WDT_H
 #define __ARCH_ARM_SRC_SAMD5E5_HARDWARE_SAM_WDT_H
 
-/********************************************************************************************
+/****************************************************************************
  * Included Files
- ********************************************************************************************/
+ ****************************************************************************/
 
 #include <nuttx/config.h>
 
 #include "hardware/sam_memorymap.h"
 
-/********************************************************************************************
+/****************************************************************************
  * Pre-processor Definitions
- ********************************************************************************************/
+ ****************************************************************************/
 
-/* WDT register offsets *********************************************************************/
+/* WDT register offsets *****************************************************/
 
 #define SAM_WDT_CTRLA_OFFSET       0x0000  /* Control A register */
 #define SAM_WDT_CONFIG_OFFSET      0x0001  /* Configuration register */
@@ -59,7 +48,7 @@
 #define SAM_WDT_SYNCBUSY_OFFSET    0x0008  /* Synchronization busy register */
 #define SAM_WDT_CLEAR_OFFSET       0x000c  /* Clear register */
 
-/* WDT register addresses *******************************************************************/
+/* WDT register addresses ***************************************************/
 
 #define SAM_WDT_CTRLA              (SAM_WDT_BASE + SAM_WDT_CTRLA_OFFSET)
 #define SAM_WDT_CONFIG             (SAM_WDT_BASE + SAM_WDT_CONFIG_OFFSET)
@@ -70,7 +59,7 @@
 #define SAM_WDT_SYNCBUSY           (SAM_WDT_BASE + SAM_WDT_SYNCBUSY_OFFSET)
 #define SAM_WDT_CLEAR              (SAM_WDT_BASE + SAM_WDT_CLEAR_OFFSET)
 
-/* WDT register bit definitions *************************************************************/
+/* WDT register bit definitions *********************************************/
 
 /* Control register */
 
@@ -80,33 +69,34 @@
 
 /* Configuration register */
 
-#define WDT_CONFIG_PER_SHIFT       (0)       /* Bits 0�3: Time-Out Period */
+#define WDT_CONFIG_PER_SHIFT       (0)                              /* Bits 0�3: Time-Out Period */
 #define WDT_CONFIG_PER_MASK        (15 << WDT_CONFIG_PER_SHIFT)
-#  define WDT_CONFIG_PER_8         (0  << WDT_CONFIG_PER_SHIFT) /* 8 clock cycles */
-#  define WDT_CONFIG_PER_16        (1  << WDT_CONFIG_PER_SHIFT) /* 16 clock cycles */
-#  define WDT_CONFIG_PER_32        (2  << WDT_CONFIG_PER_SHIFT) /* 32 clock cycles */
-#  define WDT_CONFIG_PER_64        (3  << WDT_CONFIG_PER_SHIFT) /* 64 clock cycles */
-#  define WDT_CONFIG_PER_128       (4  << WDT_CONFIG_PER_SHIFT) /* 128 clock cycles */
-#  define WDT_CONFIG_PER_256       (5  << WDT_CONFIG_PER_SHIFT) /* 256 clocks cycles */
-#  define WDT_CONFIG_PER_512       (6  << WDT_CONFIG_PER_SHIFT) /* 512 clocks cycles */
-#  define WDT_CONFIG_PER_1K        (7  << WDT_CONFIG_PER_SHIFT) /* 1024 clock cycles */
-#  define WDT_CONFIG_PER_2K        (8  << WDT_CONFIG_PER_SHIFT) /* 2048 clock cycles */
-#  define WDT_CONFIG_PER_4K        (9  << WDT_CONFIG_PER_SHIFT) /* 4096 clock cycles */
-#  define WDT_CONFIG_PER_8K        (10 << WDT_CONFIG_PER_SHIFT) /* 8192 clock cycles */
-#  define WDT_CONFIG_PER_16K       (11 << WDT_CONFIG_PER_SHIFT) /* 16384 clock cycles */
-#define WDT_CONFIG_WINDOW_SHIFT    (4)       /* Bits 4-7: Window Mode Time-Out Period */
+#  define WDT_CONFIG_PER_8         (0  << WDT_CONFIG_PER_SHIFT)     /* 8 clock cycles */
+#  define WDT_CONFIG_PER_16        (1  << WDT_CONFIG_PER_SHIFT)     /* 16 clock cycles */
+#  define WDT_CONFIG_PER_32        (2  << WDT_CONFIG_PER_SHIFT)     /* 32 clock cycles */
+#  define WDT_CONFIG_PER_64        (3  << WDT_CONFIG_PER_SHIFT)     /* 64 clock cycles */
+#  define WDT_CONFIG_PER_128       (4  << WDT_CONFIG_PER_SHIFT)     /* 128 clock cycles */
+#  define WDT_CONFIG_PER_256       (5  << WDT_CONFIG_PER_SHIFT)     /* 256 clocks cycles */
+#  define WDT_CONFIG_PER_512       (6  << WDT_CONFIG_PER_SHIFT)     /* 512 clocks cycles */
+#  define WDT_CONFIG_PER_1K        (7  << WDT_CONFIG_PER_SHIFT)     /* 1024 clock cycles */
+#  define WDT_CONFIG_PER_2K        (8  << WDT_CONFIG_PER_SHIFT)     /* 2048 clock cycles */
+#  define WDT_CONFIG_PER_4K        (9  << WDT_CONFIG_PER_SHIFT)     /* 4096 clock cycles */
+#  define WDT_CONFIG_PER_8K        (10 << WDT_CONFIG_PER_SHIFT)     /* 8192 clock cycles */
+#  define WDT_CONFIG_PER_16K       (11 << WDT_CONFIG_PER_SHIFT)     /* 16384 clock cycles */
+
+#define WDT_CONFIG_WINDOW_SHIFT    (4)                              /* Bits 4-7: Window Mode Time-Out Period */
 #define WDT_CONFIG_WINDOW_MASK     (15 << WDT_CONFIG_WINDOW_SHIFT)
-#  define WDT_CONFIG_WINDOW_8      (0  << WDT_CONFIG_WINDOW_SHIFT) /* 8 clock cycles */
-#  define WDT_CONFIG_WINDOW_16     (1  << WDT_CONFIG_WINDOW_SHIFT) /* 16 clock cycles */
-#  define WDT_CONFIG_WINDOW_32     (2  << WDT_CONFIG_WINDOW_SHIFT) /* 32 clock cycles */
-#  define WDT_CONFIG_WINDOW_64     (3  << WDT_CONFIG_WINDOW_SHIFT) /* 64 clock cycles */
-#  define WDT_CONFIG_WINDOW_128    (4  << WDT_CONFIG_WINDOW_SHIFT) /* 128 clock cycles */
-#  define WDT_CONFIG_WINDOW_256    (5  << WDT_CONFIG_WINDOW_SHIFT) /* 256 clocks cycles */
-#  define WDT_CONFIG_WINDOW_512    (6  << WDT_CONFIG_WINDOW_SHIFT) /* 512 clocks cycles */
-#  define WDT_CONFIG_WINDOW_1K     (7  << WDT_CONFIG_WINDOW_SHIFT) /* 1024 clock cycles */
-#  define WDT_CONFIG_WINDOW_2K     (8  << WDT_CONFIG_WINDOW_SHIFT) /* 2048 clock cycles */
-#  define WDT_CONFIG_WINDOW_4K     (9  << WDT_CONFIG_WINDOW_SHIFT) /* 4096 clock cycles */
-#  define WDT_CONFIG_WINDOW_8k     (10 << WDT_CONFIG_WINDOW_SHIFT) /* 8192 clock cycles */
+#  define WDT_CONFIG_WINDOW_8      (0  << WDT_CONFIG_WINDOW_SHIFT)  /* 8 clock cycles */
+#  define WDT_CONFIG_WINDOW_16     (1  << WDT_CONFIG_WINDOW_SHIFT)  /* 16 clock cycles */
+#  define WDT_CONFIG_WINDOW_32     (2  << WDT_CONFIG_WINDOW_SHIFT)  /* 32 clock cycles */
+#  define WDT_CONFIG_WINDOW_64     (3  << WDT_CONFIG_WINDOW_SHIFT)  /* 64 clock cycles */
+#  define WDT_CONFIG_WINDOW_128    (4  << WDT_CONFIG_WINDOW_SHIFT)  /* 128 clock cycles */
+#  define WDT_CONFIG_WINDOW_256    (5  << WDT_CONFIG_WINDOW_SHIFT)  /* 256 clocks cycles */
+#  define WDT_CONFIG_WINDOW_512    (6  << WDT_CONFIG_WINDOW_SHIFT)  /* 512 clocks cycles */
+#  define WDT_CONFIG_WINDOW_1K     (7  << WDT_CONFIG_WINDOW_SHIFT)  /* 1024 clock cycles */
+#  define WDT_CONFIG_WINDOW_2K     (8  << WDT_CONFIG_WINDOW_SHIFT)  /* 2048 clock cycles */
+#  define WDT_CONFIG_WINDOW_4K     (9  << WDT_CONFIG_WINDOW_SHIFT)  /* 4096 clock cycles */
+#  define WDT_CONFIG_WINDOW_8k     (10 << WDT_CONFIG_WINDOW_SHIFT)  /* 8192 clock cycles */
 
 /* Early warning interrupt control register */
 
@@ -125,8 +115,8 @@
 #  define WDT_EWCTRL_EWOFFSET_8k   (10 << WDT_EWCTRL_EWOFFSET_SHIFT) /* 8192 clock cycles */
 #  define WDT_EWCTRL_EWOFFSET_16K  (11 << WDT_EWCTRL_EWOFFSET_SHIFT) /* 16384 clock cycles */
 
-/* Interrupt enable clear, interrupt enable set register, interrupt flag status and clear
- * registers
+/* Interrupt enable clear, interrupt enable set register,
+ * interrupt flag status and clear registers.
  */
 
 #define WDT_INT_EW                 (1 << 0)  /* Bit 0:  Early warning interrupt */
@@ -145,16 +135,12 @@
 #define WDT_CLEAR_CLEAR_MASK       (0xff << WDT_CLEAR_CLEAR_SHIFT)
 #  define WDT_CLEAR_CLEAR          (0xa5 << WDT_CLEAR_CLEAR_SHIFT)
 
-/********************************************************************************************
+/****************************************************************************
  * Public Types
- ********************************************************************************************/
+ ****************************************************************************/
 
-/********************************************************************************************
+/****************************************************************************
  * Public Data
- ********************************************************************************************/
-
-/********************************************************************************************
- * Public Functions
- ********************************************************************************************/
+ ****************************************************************************/
 
 #endif /* __ARCH_ARM_SRC_SAMD5E5_HARDWARE_SAM_WDT_H */
diff --git a/arch/arm/src/samd5e5/sam_wdt.c b/arch/arm/src/samd5e5/sam_wdt.c
index 070ab13..c86261a 100644
--- a/arch/arm/src/samd5e5/sam_wdt.c
+++ b/arch/arm/src/samd5e5/sam_wdt.c
@@ -1,36 +1,24 @@
 /****************************************************************************
  * arch/arm/src/samd5e5/sam_wdt.c
  *
- *   Copyright (C) 2020 Falker Automacao Agricola LTDA.
+ *   Copyright 2020 Falker Automacao Agricola LTDA.
  *   Author: Leomar Mateus Radke <le...@falker.com.br>
  *   Author: Ricardo Wartchow <wa...@gmail.com>
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * 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.
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -69,42 +57,34 @@
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
-/* Clocking *****************************************************************/
-
-/** 8 clock cycles */
-#define WDT_CLK_8CYCLE 8
-/** 16 clock cycles */
-#define WDT_CLK_16CYCLE 16
-/** 32 clock cycles */
-#define WDT_CLK_32CYCLE 32
-/** 64 clock cycles */
-#define WDT_CLK_64CYCLE 64
-/** 128 clock cycles */
-#define WDT_CLK_128CYCLE 128
-/** 256 clock cycles */
-#define WDT_CLK_256CYCLE 256
-/** 512 clock cycles */
-#define WDT_CLK_512CYCLE 512
-/** 1024 clock cycles */
-#define WDT_CLK_1024CYCLE 1024
-/** 20488 clock cycles */
-#define WDT_CLK_2048CYCLE 2048
-/** 4096 clock cycles */
-#define WDT_CLK_4096CYCLE 4096
-/** 8192 clock cycles */
-#define WDT_CLK_8192CYCLE 8192
-/** 16384 clock cycles */
-#define WDT_CLK_16384CYCLE 16384
+
+/** N clock cycles */
+
+#define WDT_CLK_8CYCLE      8 
+#define WDT_CLK_16CYCLE     16
+#define WDT_CLK_32CYCLE     32
+#define WDT_CLK_64CYCLE     64
+#define WDT_CLK_128CYCLE    128
+#define WDT_CLK_256CYCLE    256
+#define WDT_CLK_512CYCLE    512
+#define WDT_CLK_1024CYCLE   1024
+#define WDT_CLK_2048CYCLE   2048
+#define WDT_CLK_4096CYCLE   4096
+#define WDT_CLK_8192CYCLE   8192
+#define WDT_CLK_16384CYCLE  16384
 
 /**
  * \brief Macro is used to indicate the rate of second/millisecond
  */
+
 #define WDT_PERIOD_RATE 1000
 
 /****************************************************************************
  * Private Types
  ****************************************************************************/
-/* This structure provides the private representation of the "lower-half"
+
+/**
+ * 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.
  */
@@ -112,22 +92,18 @@
 struct sam_lowerhalf_s
 {
   FAR const struct watchdog_ops_s  *ops;  /* Lower half operations */
-  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 */
+  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
  ****************************************************************************/
-void sam_sync_wdt(int value);
 
-/* Register operations ******************************************************/
-
-
-/*static int      sam_interrupt(int irq, FAR void *context, FAR void *arg);*/
+void sam_sync_wdt(int value);
 
 /* "Lower half" driver methods **********************************************/
 
@@ -138,14 +114,11 @@ static int      sam_getstatus(FAR struct watchdog_lowerhalf_s *lower,
                   FAR struct watchdog_status_s *status);
 static int      sam_settimeout(FAR struct watchdog_lowerhalf_s *lower,
                   uint32_t timeout);
-/*static xcpt_t   sam_capture(FAR struct watchdog_lowerhalf_s *lower,
-                  xcpt_t handler);
-static int      sam_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 =
@@ -166,6 +139,7 @@ static struct sam_lowerhalf_s g_wdgdev;
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
+
 void sam_sync_wdt(int value)
 {
   while ((getreg32(SAM_WDT_SYNCBUSY) & value) != 0);
@@ -182,19 +156,6 @@ void sam_wdt_dumpregs(void)
   wdinfo("          EWC:  %02x\n", getreg8(SAM_WDT_EWCTRL));
   wdinfo("        CLEAR:  %02x\n", getreg8(SAM_WDT_CLEAR));
 }
-/****************************************************************************
- * Name: sam_interrupt
- *
- * Description:
- *   WDT interrupt
- *
- * Input Parameters:
- *   Usual interrupt handler arguments.
- *
- * Returned Value:
- *   Always returns OK.
- *
- ****************************************************************************/
 
 /****************************************************************************
  * Name: sam_start
@@ -203,8 +164,8 @@ void sam_wdt_dumpregs(void)
  *   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 the publicly visible representation
+ *  of the "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -227,22 +188,22 @@ static int sam_start(FAR struct watchdog_lowerhalf_s *lower)
        * starting the watchdog timer.
        */
 
-       /* 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.
+      /* Enable IWDG (the LSI oscillator will be enabled by hardware).
+       * If the "Hardware watchdog" feature is enabled
+       * through the device option bits,
+       * the watchdog is automatically enabled at power-on.
        */
 
-      flags           = enter_critical_section();
-      
-      /*putreg8(WDT_CTRLA_ENABLE, SAM_WDT_CTRLA);
-      sam_sync_wdt(WDT_SYNCBUSY_ENABLE);*/
-      
+      flags = enter_critical_section();
+
+      putreg8(WDT_CTRLA_ENABLE, SAM_WDT_CTRLA);
+      sam_sync_wdt(WDT_SYNCBUSY_ENABLE);
       priv->lastreset = clock_systime_ticks();
-      
       priv->started   = true;
-      
+
       leave_critical_section(flags);
     }
+
   return OK;
 }
 
@@ -253,8 +214,8 @@ static int sam_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 the publicly visible representation of
+ *           the "lower-half" driver state structure.
  *
  * Returned Value:
  *   Zero on success; a negated errno value on failure.
@@ -280,12 +241,12 @@ static int sam_stop(FAR struct watchdog_lowerhalf_s *lower)
  *   imminent watchdog timeouts.  This is sometimes referred as "pinging"
  *   the watchdog timer or "petting the dog".
  *
- *   The application program must write in the SAM_WDT_CLEAR register at regular
- *   intervals during normal operation to prevent an MCU reset.
+ *   The application program must write in the SAM_WDT_CLEAR register
+ *   at regular intervals during normal operation to prevent an MCU reset.
  *
  * Input Parameters:
- *   lower - A pointer the publicly visible representation of the "lower-half"
- *           driver state structure.
+ *   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.
@@ -295,16 +256,15 @@ static int sam_stop(FAR struct watchdog_lowerhalf_s *lower)
 static int sam_keepalive(FAR struct watchdog_lowerhalf_s *lower)
 {
   FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
- irqstate_t flags;
+  irqstate_t flags;
 
-  wdinfo("Entry\n");
   /* Reload the WDT timer */
 
   flags = enter_critical_section();
 
   putreg32(WDT_CLEAR_CLEAR, SAM_WDT_CLEAR);
   priv->lastreset = clock_systime_ticks();
-  
+
   leave_critical_section(flags);
   return OK;
 }
@@ -316,8 +276,8 @@ static int sam_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 the publicly visible representation of
+ *            the "lower-half" driver state structure.
  *   status - The location to return the watchdog status information.
  *
  * Returned Value:
@@ -375,8 +335,8 @@ static int sam_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 the publicly visible representation of
+ *             the "lower-half" driver state structure.
  *   timeout - The new timeout value in millisecnds.
  *
  * Returned Value:
@@ -392,80 +352,73 @@ static int sam_settimeout(FAR struct watchdog_lowerhalf_s *lower,
   uint32_t            period_cycles;
   uint8_t             timeout_period = WDT_CONFIG_PER_16K;
   irqstate_t flags;
- 
+
   DEBUGASSERT(priv);
   wdinfo("Entry: timeout=%d\n", timeout);
 
   /* Can this timeout be represented? */
 
   flags = enter_critical_section();
-  
+
   /* calc the period cycles corresponding to timeout period */
+
   tmp = (uint64_t)timeout * WDT_PERIOD_RATE;
 
-  /* check whether overflow*/
+  /* check whether overflow */
+
   if (tmp >> 32)
-    return -ERANGE;
+  return -ERANGE;
 
   period_cycles = (uint32_t)tmp;
+
   /* calc the register value corresponding to period cysles */
-  switch (period_cycles) 
+
+  switch (period_cycles)
   {
     case WDT_CLK_8CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_8;
     break;
-    
     case WDT_CLK_16CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_16;
     break;
-    
     case WDT_CLK_32CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_32;
     break;
-    
     case WDT_CLK_64CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_64;
     break;
-    
     case WDT_CLK_128CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_128;
     break;
-    
     case WDT_CLK_256CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_256;
     break;
-    
     case WDT_CLK_512CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_512;
     break;
-    
     case WDT_CLK_1024CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_1K;
     break;
-    
     case WDT_CLK_2048CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_2K;
     break;
-    
     case WDT_CLK_4096CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_4K;
     break;
-    
     case WDT_CLK_8192CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_8K;
     break;
-    
     case WDT_CLK_16384CYCLE *WDT_PERIOD_RATE:
       timeout_period = WDT_CONFIG_PER_16K;
     break;
   }
 
-  if(!priv->started)
+  if (!priv->started)
     putreg8(WDT_CONFIG_PER_16K, SAM_WDT_CONFIG);
   else
     putreg8(timeout_period, SAM_WDT_CONFIG);
-  
-  priv->reload = timeout_period;  
+
+  priv->reload = timeout_period;
   wdinfo("fwdt=%d reload=%d timout=%d\n",
          WDT_FCLK, timeout_period, priv->timeout);
   leave_critical_section(flags);
@@ -481,8 +434,8 @@ static int sam_settimeout(FAR struct watchdog_lowerhalf_s *lower,
  * Name: sam_wdt_initialize
  *
  * Description:
- *   Initialize the WDT watchdog timer.  The watchdog timer is initialized and
- *   registers as 'devpath'.
+ *   Initialize the WDT watchdog timer.  The watchdog timer
+ *   is initialized and registers as 'devpath'.
  *
  * Input Parameters:
  *   devpath - The full path to the watchdog.  This should be of the form
@@ -492,23 +445,20 @@ static int sam_settimeout(FAR struct watchdog_lowerhalf_s *lower,
  *   None
  *
  ****************************************************************************/
+
 void sam_wdt_initialize(FAR const char *devpath)
 {
   FAR struct sam_lowerhalf_s *priv = &g_wdgdev;
-  
   DEBUGASSERT((getreg8(SAM_WDT_CTRLA) & WDT_CTRLA_ENABLE) == 0);
-
   sam_apb_wdt_enableperiph();
-  
-  
-  /* Initialize the driver state structure. */
-   priv->ops = &g_wdgops;
-   priv->started = false;  
 
-  sam_settimeout((FAR struct watchdog_lowerhalf_s *)priv, BOARD_SCLK_FREQUENCY/2);
+  /* Initialize the driver state structure. */
 
+  priv->ops = &g_wdgops;
+  priv->started = false;
+  sam_settimeout((FAR struct watchdog_lowerhalf_s *)priv,
+                  BOARD_SCLK_FREQUENCY / 2);
   (void)watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv);
-
 }
 
 #endif /* CONFIG_WATCHDOG && CONFIG__WDT */
diff --git a/arch/arm/src/samd5e5/sam_wdt.h b/arch/arm/src/samd5e5/sam_wdt.h
index 7403f0d..a8c3777 100644
--- a/arch/arm/src/samd5e5/sam_wdt.h
+++ b/arch/arm/src/samd5e5/sam_wdt.h
@@ -1,36 +1,24 @@
 /****************************************************************************
- * arch/arm/src/sama5/sam_wdt.h
+ * arch/arm/src/samd5e5/sam_wdt.h
  *
- *   Copyright (C) 2020 Falker Automacao Agricola LTDA.
+ *   Copyright 2020 Falker Automacao Agricola LTDA.
  *   Author: Leomar Mateus Radke <le...@falker.com.br>
  *   Author: Ricardo Wartchow <wa...@gmail.com>
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * 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.
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
@@ -64,7 +52,7 @@ extern "C"
 #endif
 
 /****************************************************************************
- * Public Functions
+ * Public Function Prototypes
  ****************************************************************************/
 
 /****************************************************************************


[incubator-nuttx] 01/02: arch: samd5e5 : Add watchdog timer drivers.

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

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

commit e7073df8d622777ceb51594b8bfb4a6fb20ac66e
Author: leomarradke <le...@falker.com.br>
AuthorDate: Mon Aug 3 20:41:10 2020 -0300

    arch: samd5e5 : Add watchdog timer drivers.
    
    boards: metro-m4  Add support for starting the watchdog timer on the metro-m4.
    
    Testing:
    - Build check only
    
    Signed-off-by: Leomar Mateus Radke  <le...@falker.com.br>
---
 arch/arm/src/samd5e5/hardware/sam_wdt.h            |   2 +-
 arch/arm/src/samd5e5/sam_wdt.c                     | 514 +++++++++++++++++++++
 .../arm/src/samd5e5/sam_wdt.h                      |  68 +--
 boards/arm/samd5e5/metro-m4/src/sam_bringup.c      |   8 +
 4 files changed, 560 insertions(+), 32 deletions(-)

diff --git a/arch/arm/src/samd5e5/hardware/sam_wdt.h b/arch/arm/src/samd5e5/hardware/sam_wdt.h
index 53e2afd..d8024f5 100644
--- a/arch/arm/src/samd5e5/hardware/sam_wdt.h
+++ b/arch/arm/src/samd5e5/hardware/sam_wdt.h
@@ -92,7 +92,7 @@
 #  define WDT_CONFIG_PER_1K        (7  << WDT_CONFIG_PER_SHIFT) /* 1024 clock cycles */
 #  define WDT_CONFIG_PER_2K        (8  << WDT_CONFIG_PER_SHIFT) /* 2048 clock cycles */
 #  define WDT_CONFIG_PER_4K        (9  << WDT_CONFIG_PER_SHIFT) /* 4096 clock cycles */
-#  define WDT_CONFIG_PER_8k        (10 << WDT_CONFIG_PER_SHIFT) /* 8192 clock cycles */
+#  define WDT_CONFIG_PER_8K        (10 << WDT_CONFIG_PER_SHIFT) /* 8192 clock cycles */
 #  define WDT_CONFIG_PER_16K       (11 << WDT_CONFIG_PER_SHIFT) /* 16384 clock cycles */
 #define WDT_CONFIG_WINDOW_SHIFT    (4)       /* Bits 4-7: Window Mode Time-Out Period */
 #define WDT_CONFIG_WINDOW_MASK     (15 << WDT_CONFIG_WINDOW_SHIFT)
diff --git a/arch/arm/src/samd5e5/sam_wdt.c b/arch/arm/src/samd5e5/sam_wdt.c
new file mode 100644
index 0000000..070ab13
--- /dev/null
+++ b/arch/arm/src/samd5e5/sam_wdt.c
@@ -0,0 +1,514 @@
+/****************************************************************************
+ * arch/arm/src/samd5e5/sam_wdt.c
+ *
+ *   Copyright (C) 2020 Falker Automacao Agricola LTDA.
+ *   Author: Leomar Mateus Radke <le...@falker.com.br>
+ *   Author: Ricardo Wartchow <wa...@gmail.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 <nuttx/arch.h>
+
+#include <sys/types.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 "arm_internal.h"
+#include "arm_arch.h"
+#include "sam_periphclks.h"
+#include "sam_wdt.h"
+
+#if defined(CONFIG_WATCHDOG) && defined(CONFIG_SAMD5E5_WDT)
+
+#ifndef BOARD_SCLK_FREQUENCY
+#  define BOARD_SCLK_FREQUENCY 32768
+#endif
+
+#define WDT_FCLK        (BOARD_SCLK_FREQUENCY / 128)
+#define WDT_MAXTIMEOUT  ((1000 * (WDT_MR_WDV_MAX+1)) / WDT_FCLK)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Clocking *****************************************************************/
+
+/** 8 clock cycles */
+#define WDT_CLK_8CYCLE 8
+/** 16 clock cycles */
+#define WDT_CLK_16CYCLE 16
+/** 32 clock cycles */
+#define WDT_CLK_32CYCLE 32
+/** 64 clock cycles */
+#define WDT_CLK_64CYCLE 64
+/** 128 clock cycles */
+#define WDT_CLK_128CYCLE 128
+/** 256 clock cycles */
+#define WDT_CLK_256CYCLE 256
+/** 512 clock cycles */
+#define WDT_CLK_512CYCLE 512
+/** 1024 clock cycles */
+#define WDT_CLK_1024CYCLE 1024
+/** 20488 clock cycles */
+#define WDT_CLK_2048CYCLE 2048
+/** 4096 clock cycles */
+#define WDT_CLK_4096CYCLE 4096
+/** 8192 clock cycles */
+#define WDT_CLK_8192CYCLE 8192
+/** 16384 clock cycles */
+#define WDT_CLK_16384CYCLE 16384
+
+/**
+ * \brief Macro is used to indicate the rate of second/millisecond
+ */
+#define WDT_PERIOD_RATE 1000
+
+/****************************************************************************
+ * 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 sam_lowerhalf_s
+{
+  FAR const struct watchdog_ops_s  *ops;  /* Lower half operations */
+  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
+ ****************************************************************************/
+void sam_sync_wdt(int value);
+
+/* Register operations ******************************************************/
+
+
+/*static int      sam_interrupt(int irq, FAR void *context, FAR void *arg);*/
+
+/* "Lower half" driver methods **********************************************/
+
+static int      sam_start(FAR struct watchdog_lowerhalf_s *lower);
+static int      sam_stop(FAR struct watchdog_lowerhalf_s *lower);
+static int      sam_keepalive(FAR struct watchdog_lowerhalf_s *lower);
+static int      sam_getstatus(FAR struct watchdog_lowerhalf_s *lower,
+                  FAR struct watchdog_status_s *status);
+static int      sam_settimeout(FAR struct watchdog_lowerhalf_s *lower,
+                  uint32_t timeout);
+/*static xcpt_t   sam_capture(FAR struct watchdog_lowerhalf_s *lower,
+                  xcpt_t handler);
+static int      sam_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      = sam_start,
+  .stop       = sam_stop,
+  .keepalive  = sam_keepalive,
+  .getstatus  = sam_getstatus,
+  .settimeout = sam_settimeout,
+  .capture    = NULL,
+  .ioctl      = NULL,
+};
+
+/* "Lower half" driver state */
+
+static struct sam_lowerhalf_s g_wdgdev;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+void sam_sync_wdt(int value)
+{
+  while ((getreg32(SAM_WDT_SYNCBUSY) & value) != 0);
+}
+
+void sam_wdt_dumpregs(void)
+{
+  wdinfo("WDT  Regs:\n");
+  wdinfo("     INTENCLR:  %02x\n", getreg8(SAM_WDT_INTENCLR));
+  wdinfo("     INTENSET:  %02x\n", getreg8(SAM_WDT_INTENSET));
+  wdinfo("      INTFLAG:  %02x\n", getreg8(SAM_WDT_INTFLAG));
+  wdinfo("        CTRLA:  %02x\n", getreg8(SAM_WDT_CTRLA));
+  wdinfo("       CONFIG:  %02x\n", getreg8(SAM_WDT_CONFIG));
+  wdinfo("          EWC:  %02x\n", getreg8(SAM_WDT_EWCTRL));
+  wdinfo("        CLEAR:  %02x\n", getreg8(SAM_WDT_CLEAR));
+}
+/****************************************************************************
+ * Name: sam_interrupt
+ *
+ * Description:
+ *   WDT interrupt
+ *
+ * Input Parameters:
+ *   Usual interrupt handler arguments.
+ *
+ * Returned Value:
+ *   Always returns OK.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_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 sam_start(FAR struct watchdog_lowerhalf_s *lower)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
+  irqstate_t flags;
+
+  wdinfo("Entry: started=%d\n");
+  DEBUGASSERT(priv);
+
+  /* Have we already been started? */
+
+  if (!priv->started)
+    {
+      /* Set up prescaler and reload value for the selected timeout before
+       * starting the watchdog timer.
+       */
+
+       /* 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();
+      
+      /*putreg8(WDT_CTRLA_ENABLE, SAM_WDT_CTRLA);
+      sam_sync_wdt(WDT_SYNCBUSY_ENABLE);*/
+      
+      priv->lastreset = clock_systime_ticks();
+      
+      priv->started   = true;
+      
+      leave_critical_section(flags);
+    }
+  return OK;
+}
+
+/****************************************************************************
+ * Name: sam_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 sam_stop(FAR struct watchdog_lowerhalf_s *lower)
+{
+  /* The watchdog is always disabled after a reset. It is enabled by clearing
+   * the WDDIS bit in the WDT_CR register, then it cannot be disabled again
+   * except by a reset.
+   */
+
+  wdinfo("Entry\n");
+  return -ENOSYS;
+}
+
+/****************************************************************************
+ * Name: sam_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 SAM_WDT_CLEAR register at regular
+ *   intervals during normal operation to prevent an MCU reset.
+ *
+ * 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 sam_keepalive(FAR struct watchdog_lowerhalf_s *lower)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
+ irqstate_t flags;
+
+  wdinfo("Entry\n");
+  /* Reload the WDT timer */
+
+  flags = enter_critical_section();
+
+  putreg32(WDT_CLEAR_CLEAR, SAM_WDT_CLEAR);
+  priv->lastreset = clock_systime_ticks();
+  
+  leave_critical_section(flags);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: sam_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 sam_getstatus(FAR struct watchdog_lowerhalf_s *lower,
+                           FAR struct watchdog_status_s *status)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_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_systime_ticks() - 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: sam_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 millisecnds.
+ *
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int sam_settimeout(FAR struct watchdog_lowerhalf_s *lower,
+                            uint32_t timeout)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
+  uint64_t            tmp;
+  uint32_t            period_cycles;
+  uint8_t             timeout_period = WDT_CONFIG_PER_16K;
+  irqstate_t flags;
+ 
+  DEBUGASSERT(priv);
+  wdinfo("Entry: timeout=%d\n", timeout);
+
+  /* Can this timeout be represented? */
+
+  flags = enter_critical_section();
+  
+  /* calc the period cycles corresponding to timeout period */
+  tmp = (uint64_t)timeout * WDT_PERIOD_RATE;
+
+  /* check whether overflow*/
+  if (tmp >> 32)
+    return -ERANGE;
+
+  period_cycles = (uint32_t)tmp;
+  /* calc the register value corresponding to period cysles */
+  switch (period_cycles) 
+  {
+    case WDT_CLK_8CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_8;
+    break;
+    
+    case WDT_CLK_16CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_16;
+    break;
+    
+    case WDT_CLK_32CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_32;
+    break;
+    
+    case WDT_CLK_64CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_64;
+    break;
+    
+    case WDT_CLK_128CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_128;
+    break;
+    
+    case WDT_CLK_256CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_256;
+    break;
+    
+    case WDT_CLK_512CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_512;
+    break;
+    
+    case WDT_CLK_1024CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_1K;
+    break;
+    
+    case WDT_CLK_2048CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_2K;
+    break;
+    
+    case WDT_CLK_4096CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_4K;
+    break;
+    
+    case WDT_CLK_8192CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_8K;
+    break;
+    
+    case WDT_CLK_16384CYCLE *WDT_PERIOD_RATE:
+      timeout_period = WDT_CONFIG_PER_16K;
+    break;
+  }
+
+  if(!priv->started)
+    putreg8(WDT_CONFIG_PER_16K, SAM_WDT_CONFIG);
+  else
+    putreg8(timeout_period, SAM_WDT_CONFIG);
+  
+  priv->reload = timeout_period;  
+  wdinfo("fwdt=%d reload=%d timout=%d\n",
+         WDT_FCLK, timeout_period, priv->timeout);
+  leave_critical_section(flags);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_wdt_initialize
+ *
+ * Description:
+ *   Initialize the WDT watchdog timer.  The watchdog timer is initialized and
+ *   registers as 'devpath'.
+ *
+ * Input Parameters:
+ *   devpath - The full path to the watchdog.  This should be of the form
+ *     /dev/watchdog0
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+void sam_wdt_initialize(FAR const char *devpath)
+{
+  FAR struct sam_lowerhalf_s *priv = &g_wdgdev;
+  
+  DEBUGASSERT((getreg8(SAM_WDT_CTRLA) & WDT_CTRLA_ENABLE) == 0);
+
+  sam_apb_wdt_enableperiph();
+  
+  
+  /* Initialize the driver state structure. */
+   priv->ops = &g_wdgops;
+   priv->started = false;  
+
+  sam_settimeout((FAR struct watchdog_lowerhalf_s *)priv, BOARD_SCLK_FREQUENCY/2);
+
+  (void)watchdog_register(devpath, (FAR struct watchdog_lowerhalf_s *)priv);
+
+}
+
+#endif /* CONFIG_WATCHDOG && CONFIG__WDT */
diff --git a/boards/arm/samd5e5/metro-m4/src/sam_bringup.c b/arch/arm/src/samd5e5/sam_wdt.h
similarity index 69%
copy from boards/arm/samd5e5/metro-m4/src/sam_bringup.c
copy to arch/arm/src/samd5e5/sam_wdt.h
index 4f66060..7403f0d 100644
--- a/boards/arm/samd5e5/metro-m4/src/sam_bringup.c
+++ b/arch/arm/src/samd5e5/sam_wdt.h
@@ -1,8 +1,9 @@
 /****************************************************************************
- * boards/arm/samd5e5/metro-m4/src/sam_bringup.c
+ * arch/arm/src/sama5/sam_wdt.h
  *
- *   Copyright (C) 2018 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ *   Copyright (C) 2020 Falker Automacao Agricola LTDA.
+ *   Author: Leomar Mateus Radke <le...@falker.com.br>
+ *   Author: Ricardo Wartchow <wa...@gmail.com>
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions
@@ -33,59 +34,64 @@
  *
  ****************************************************************************/
 
+#ifndef __ARCH_ARM_SRC_SAMD5E5_SAM_WDT_H
+#define __ARCH_ARM_SRC_SAMD5E5_SAM_WDT_H
+
 /****************************************************************************
  * Included Files
  ****************************************************************************/
 
 #include <nuttx/config.h>
 
-#include <sys/mount.h>
-#include <stdbool.h>
-#include <stdio.h>
-#include <debug.h>
-#include <errno.h>
+#include "chip.h"
+#include "hardware/sam_wdt.h"
 
-#include "metro-m4.h"
+#ifdef CONFIG_SAMD5E5_WDT
 
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
 
-#define PROCFS_MOUNTPOINT "/proc"
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
 
 /****************************************************************************
  * Public Functions
  ****************************************************************************/
 
 /****************************************************************************
- * Name: sam_bringup
+ * Name: sam_wdt_initialize()
  *
  * Description:
- *   Perform architecture-specific initialization
+ *   Perform architecture-specific initialization of the Watchdog hardware.
+ *   This interface should be provided by all configurations using
+ *   to avoid exposed platform-dependent logic.
+ *
+ *   At a minimum, this function should call watchdog_register().
  *
- *   CONFIG_BOARD_LATE_INITIALIZE=y :
- *     Called from board_late_initialize().
+ * Input Parameters:
+ *   None
  *
- *   CONFIG_BOARD_LATE_INITIALIZE=n && CONFIG_LIB_BOARDCTL=y :
- *     Called from the NSH library
+ * Returned Value:
+ *   Zero on success; a negated errno value on failure.
  *
  ****************************************************************************/
 
-int sam_bringup(void)
-{
-  int ret = OK;
-
-#ifdef CONFIG_FS_PROCFS
-  /* Mount the procfs file system */
+void sam_wdt_initialize(FAR const char *devpath);
 
-  ret = mount(NULL, PROCFS_MOUNTPOINT, "procfs", 0, NULL);
-  if (ret < 0)
-    {
-      syslot(LOG_ERR, "ERROR: Failed to mount procfs at %s: %d\n",
-             PROCFS_MOUNTPOINT, ret);
-    }
+#undef EXTERN
+#if defined(__cplusplus)
+}
 #endif
 
-  UNUSED(ret);
-  return OK;
-}
+#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_SAMD5E5_WDT */
+#endif /* __ARCH_ARM_SRC_SAMD5E5_SAM_WDT_H */
diff --git a/boards/arm/samd5e5/metro-m4/src/sam_bringup.c b/boards/arm/samd5e5/metro-m4/src/sam_bringup.c
index 4f66060..d5be455 100644
--- a/boards/arm/samd5e5/metro-m4/src/sam_bringup.c
+++ b/boards/arm/samd5e5/metro-m4/src/sam_bringup.c
@@ -47,6 +47,10 @@
 
 #include "metro-m4.h"
 
+#if defined(CONFIG_SAMD5E5_WDT) && defined(CONFIG_WATCHDOG)
+  #include "sam_wdt.h"
+#endif
+
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
@@ -86,6 +90,10 @@ int sam_bringup(void)
     }
 #endif
 
+#if defined(CONFIG_SAMD5E5_WDT) && defined(CONFIG_WATCHDOG)
+  (void)sam_wdt_initialize(CONFIG_WATCHDOG_DEVPATH);
+#endif
+
   UNUSED(ret);
   return OK;
 }