summaryrefslogtreecommitdiff
path: root/nuttx/configs/stm3210e-eval
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-04-16 17:20:36 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-04-16 17:20:36 +0000
commit62fb03e8a5fe25cf15fba1c106d854a0a7cb9b1f (patch)
tree20dbb76bb0ec35303c2a9267d60c872c5c867f0d /nuttx/configs/stm3210e-eval
parent103151bb4289ed721e1beede1fb057b6b7bbc9cc (diff)
downloadpx4-nuttx-62fb03e8a5fe25cf15fba1c106d854a0a7cb9b1f.tar.gz
px4-nuttx-62fb03e8a5fe25cf15fba1c106d854a0a7cb9b1f.tar.bz2
px4-nuttx-62fb03e8a5fe25cf15fba1c106d854a0a7cb9b1f.zip
Add STM32 watchdog configuration
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4617 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/stm3210e-eval')
-rwxr-xr-xnuttx/configs/stm3210e-eval/README.txt1
-rwxr-xr-xnuttx/configs/stm3210e-eval/RIDE/defconfig1
-rw-r--r--nuttx/configs/stm3210e-eval/buttons/defconfig1
-rwxr-xr-xnuttx/configs/stm3210e-eval/composite/defconfig1
-rwxr-xr-xnuttx/configs/stm3210e-eval/nsh/defconfig1
-rw-r--r--nuttx/configs/stm3210e-eval/nsh2/defconfig1
-rw-r--r--nuttx/configs/stm3210e-eval/nx/defconfig1
-rw-r--r--nuttx/configs/stm3210e-eval/nxconsole/defconfig1
-rw-r--r--nuttx/configs/stm3210e-eval/nxlines/defconfig1
-rw-r--r--nuttx/configs/stm3210e-eval/nxtext/defconfig1
-rwxr-xr-xnuttx/configs/stm3210e-eval/ostest/defconfig1
-rw-r--r--nuttx/configs/stm3210e-eval/src/Makefile4
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_watchdog.c136
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbserial/defconfig1
-rwxr-xr-xnuttx/configs/stm3210e-eval/usbstorage/defconfig1
15 files changed, 153 insertions, 0 deletions
diff --git a/nuttx/configs/stm3210e-eval/README.txt b/nuttx/configs/stm3210e-eval/README.txt
index c356a17d5..9d7c077e8 100755
--- a/nuttx/configs/stm3210e-eval/README.txt
+++ b/nuttx/configs/stm3210e-eval/README.txt
@@ -464,6 +464,7 @@ STM3210E-EVAL-specific Configuration Options
CONFIG_STM32_TIM6
CONFIG_STM32_TIM7
CONFIG_STM32_WWDG
+ CONFIG_STM32_IWDG
CONFIG_STM32_SPI2
CONFIG_STM32_SPI4
CONFIG_STM32_USART2
diff --git a/nuttx/configs/stm3210e-eval/RIDE/defconfig b/nuttx/configs/stm3210e-eval/RIDE/defconfig
index c091d0eb2..8566de22e 100755
--- a/nuttx/configs/stm3210e-eval/RIDE/defconfig
+++ b/nuttx/configs/stm3210e-eval/RIDE/defconfig
@@ -123,6 +123,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/buttons/defconfig b/nuttx/configs/stm3210e-eval/buttons/defconfig
index c257d3606..694b9bd25 100644
--- a/nuttx/configs/stm3210e-eval/buttons/defconfig
+++ b/nuttx/configs/stm3210e-eval/buttons/defconfig
@@ -135,6 +135,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/composite/defconfig b/nuttx/configs/stm3210e-eval/composite/defconfig
index 3eb19f965..57a4c0793 100755
--- a/nuttx/configs/stm3210e-eval/composite/defconfig
+++ b/nuttx/configs/stm3210e-eval/composite/defconfig
@@ -131,6 +131,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/nsh/defconfig b/nuttx/configs/stm3210e-eval/nsh/defconfig
index c81961169..39adad92f 100755
--- a/nuttx/configs/stm3210e-eval/nsh/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh/defconfig
@@ -131,6 +131,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/nsh2/defconfig b/nuttx/configs/stm3210e-eval/nsh2/defconfig
index 3924412df..8ad609818 100644
--- a/nuttx/configs/stm3210e-eval/nsh2/defconfig
+++ b/nuttx/configs/stm3210e-eval/nsh2/defconfig
@@ -152,6 +152,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/nx/defconfig b/nuttx/configs/stm3210e-eval/nx/defconfig
index c01e283c3..359cf8150 100644
--- a/nuttx/configs/stm3210e-eval/nx/defconfig
+++ b/nuttx/configs/stm3210e-eval/nx/defconfig
@@ -131,6 +131,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/nxconsole/defconfig b/nuttx/configs/stm3210e-eval/nxconsole/defconfig
index 6b19bcde2..4c04af514 100644
--- a/nuttx/configs/stm3210e-eval/nxconsole/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxconsole/defconfig
@@ -131,6 +131,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/nxlines/defconfig b/nuttx/configs/stm3210e-eval/nxlines/defconfig
index 6eda15951..8139b7107 100644
--- a/nuttx/configs/stm3210e-eval/nxlines/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxlines/defconfig
@@ -131,6 +131,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/nxtext/defconfig b/nuttx/configs/stm3210e-eval/nxtext/defconfig
index 38f0ca074..3045de58e 100644
--- a/nuttx/configs/stm3210e-eval/nxtext/defconfig
+++ b/nuttx/configs/stm3210e-eval/nxtext/defconfig
@@ -131,6 +131,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/ostest/defconfig b/nuttx/configs/stm3210e-eval/ostest/defconfig
index 0beef4d98..62ec95cf4 100755
--- a/nuttx/configs/stm3210e-eval/ostest/defconfig
+++ b/nuttx/configs/stm3210e-eval/ostest/defconfig
@@ -133,6 +133,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/src/Makefile b/nuttx/configs/stm3210e-eval/src/Makefile
index db5710c08..be12a216f 100644
--- a/nuttx/configs/stm3210e-eval/src/Makefile
+++ b/nuttx/configs/stm3210e-eval/src/Makefile
@@ -72,6 +72,10 @@ ifeq ($(CONFIG_CAN),y)
CSRCS += up_can.c
endif
+ifeq ($(CONFIG_WATCHDOG),y)
+CSRCS += up_watchdog.c
+endif
+
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/stm3210e-eval/src/up_watchdog.c b/nuttx/configs/stm3210e-eval/src/up_watchdog.c
new file mode 100644
index 000000000..0c09f7549
--- /dev/null
+++ b/nuttx/configs/stm3210e-eval/src/up_watchdog.c
@@ -0,0 +1,136 @@
+/************************************************************************************
+ * configs/stm3210e-eval/src/up_watchdog.c
+ * arch/arm/src/board/up_watchdog.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@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 <errno.h>
+#include <debug.h>
+
+#include <nuttx/watchdog.h>
+#include <arch/board/board.h>
+
+#include "stm32_wdg.h"
+
+#ifdef CONFIG_WATCHDOG
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+/* Configuration *******************************************************************/
+/* Wathdog hardware should be enabled */
+
+#if !defined(CONFIG_STM32_WWDG) && !defined(CONFIG_STM32_IWDG)
+# warning "One of CONFIG_STM32_WWDG or CONFIG_STM32_IWDG must be defined"
+#endif
+
+/* Select the path to the registered watchdog timer device */
+
+#ifndef CONFIG_STM32_WDG_DEVPATH
+# ifdef CONFIG_EXAMPLES_WATCHDOG_DEVPATH
+# define CONFIG_STM32_WDG_DEVPATH CONFIG_EXAMPLES_WATCHDOG_DEVPATH
+# else
+# define CONFIG_STM32_WDG_DEVPATH "/dev/watchdog0"
+# endif
+#endif
+
+/* Use the un-calibrated LSI frequency if we have nothing better */
+
+#if defined(CONFIG_STM32_IWDG) && !defined(CONFIG_STM32_LSIFREQ)
+# define CONFIG_STM32_LSIFREQ STM32_LSI_FREQUENCY
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing the watchdog timer */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_WATCHDOG
+#endif
+
+#ifdef CONFIG_DEBUG_WATCHDOG
+# define wdgdbg dbg
+# define wdglldbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define wdgvdbg vdbg
+# define wdgllvdbg llvdbg
+# else
+# define wdgvdbg(x...)
+# define wdgllvdbg(x...)
+# endif
+#else
+# define wdgdbg(x...)
+# define wdglldbg(x...)
+# define wdgvdbg(x...)
+# define wdgllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/****************************************************************************
+ * Name: up_wdginitialize()
+ *
+ * Description:
+ * Perform architecuture-specific initialization of the Watchdog hardware.
+ * This interface must be provided by all configurations using
+ * apps/examples/watchdog
+ *
+ ****************************************************************************/
+
+int up_wdginitialize(void)
+{
+ /* Initialize tha register the watchdog timer device */
+
+#if defined(CONFIG_STM32_WWDG)
+ stm32_wwdginitialize(CONFIG_STM32_WDG_DEVPATH);
+ return OK;
+#elif defined(CONFIG_STM32_IWDG)
+ stm32_iwdginitialize(CONFIG_STM32_WDG_DEVPATH, CONFIG_STM32_LSIFREQ);
+ return OK;
+#else
+ return -ENODEV;
+#endif
+}
+
+#endif /* CONFIG_WATCHDOG */
diff --git a/nuttx/configs/stm3210e-eval/usbserial/defconfig b/nuttx/configs/stm3210e-eval/usbserial/defconfig
index d9f2bc89a..e9f1fea16 100755
--- a/nuttx/configs/stm3210e-eval/usbserial/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbserial/defconfig
@@ -133,6 +133,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y
diff --git a/nuttx/configs/stm3210e-eval/usbstorage/defconfig b/nuttx/configs/stm3210e-eval/usbstorage/defconfig
index 494c3f7e8..82752bbde 100755
--- a/nuttx/configs/stm3210e-eval/usbstorage/defconfig
+++ b/nuttx/configs/stm3210e-eval/usbstorage/defconfig
@@ -131,6 +131,7 @@ CONFIG_STM32_TIM5=n
CONFIG_STM32_TIM6=n
CONFIG_STM32_TIM7=n
CONFIG_STM32_WWDG=n
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI4=n
CONFIG_STM32_USART2=y