summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-23 15:25:10 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-23 15:25:10 -0600
commit1655a399b33310e02ac6b3c6ffe79c10e913203f (patch)
tree6e9d660f5fd0df7cf597f4c3bf64fff0410e0a20
parent16bff7dac782a1b01c6e27205c11e217163950c8 (diff)
downloadpx4-nuttx-1655a399b33310e02ac6b3c6ffe79c10e913203f.tar.gz
px4-nuttx-1655a399b33310e02ac6b3c6ffe79c10e913203f.tar.bz2
px4-nuttx-1655a399b33310e02ac6b3c6ffe79c10e913203f.zip
Add support for the EFM32 reset management unit (RMU). From Pierre-noel Bouteville
-rw-r--r--nuttx/arch/arm/src/efm32/Kconfig4
-rw-r--r--nuttx/arch/arm/src/efm32/Make.defs4
-rw-r--r--nuttx/arch/arm/src/efm32/efm32_rmu.c125
-rw-r--r--nuttx/arch/arm/src/efm32/efm32_rmu.h68
4 files changed, 201 insertions, 0 deletions
diff --git a/nuttx/arch/arm/src/efm32/Kconfig b/nuttx/arch/arm/src/efm32/Kconfig
index 1f7f8f852..18d6d7ec5 100644
--- a/nuttx/arch/arm/src/efm32/Kconfig
+++ b/nuttx/arch/arm/src/efm32/Kconfig
@@ -128,6 +128,10 @@ config EFM32_DMA
default n
select ARCH_DMA
+config EFM32_RMU
+ bool "Reset Management Unit (RMU) "
+ default n
+
config EFM32_USART0
bool "USART0"
default n
diff --git a/nuttx/arch/arm/src/efm32/Make.defs b/nuttx/arch/arm/src/efm32/Make.defs
index 6df8b4edd..c730fb521 100644
--- a/nuttx/arch/arm/src/efm32/Make.defs
+++ b/nuttx/arch/arm/src/efm32/Make.defs
@@ -111,6 +111,10 @@ CHIP_CSRCS += efm32_serial.c
endif
endif
+ifeq ($(CONFIG_EFM32_RMU),y)
+CHIP_CSRCS += efm32_rmu.c
+endif
+
ifeq ($(CONFIG_EFM32_USART_ISSPI),y)
CHIP_CSRCS += efm32_spi.c
endif
diff --git a/nuttx/arch/arm/src/efm32/efm32_rmu.c b/nuttx/arch/arm/src/efm32/efm32_rmu.c
new file mode 100644
index 000000000..93a16ce63
--- /dev/null
+++ b/nuttx/arch/arm/src/efm32/efm32_rmu.c
@@ -0,0 +1,125 @@
+/************************************************************************************
+ * arch/arm/src/efm32/efm32_rmu.c
+ *
+ * Copyright (C) 2015 Pierre-Noel Bouteville. All rights reserved.
+ * Author: Pierre-Noel Bouteville <pnb990@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 <stdlib.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdio.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "chip/efm32_emu.h"
+#include "chip/efm32_rmu.h"
+
+#include "emf32_rmu.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/* Variable old last reset cause of cpu. */
+
+uint32_t g_efm32_rstcause;
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: efm32_rmu_initialize
+ *
+ * Description:
+ * Store reset cause into g_efm32_rstcause then clear reset cause register.
+ *
+ ************************************************************************************/
+
+void efm32_rmu_initialize(void)
+{
+ uint32_t locked;
+
+ g_efm32_rstcause = getreg32(EFM32_RMU_RSTCAUSE);
+
+ /* Now clear reset cause */
+
+ putreg32(RMU_CMD_RCCLR,EFM32_RMU_CMD);
+
+ /* Clear some reset causes not cleared with RMU CMD register
+ * (If EMU registers locked, they must be unlocked first)
+ */
+
+ locked = getreg32(EFM32_EMU_LOCK) & EMU_LOCK_LOCKKEY_LOCKED;
+ if (locked)
+ {
+ /* EMU unlock */
+
+ putreg32(EMU_LOCK_LOCKKEY_LOCK,EMU_LOCK_LOCKKEY_UNLOCK);
+ }
+
+ modifyreg32(EFM32_EMU_AUXCTRL,0,EMU_AUXCTRL_HRCCLR);
+ modifyreg32(EFM32_EMU_AUXCTRL,EMU_AUXCTRL_HRCCLR,0);
+
+ if (locked)
+ {
+ /* EMU lock */
+
+ putreg32(EMU_LOCK_LOCKKEY_LOCK,EMU_LOCK_LOCKKEY_LOCK);
+ }
+}
diff --git a/nuttx/arch/arm/src/efm32/efm32_rmu.h b/nuttx/arch/arm/src/efm32/efm32_rmu.h
new file mode 100644
index 000000000..2887afe65
--- /dev/null
+++ b/nuttx/arch/arm/src/efm32/efm32_rmu.h
@@ -0,0 +1,68 @@
+/*****************************************************************************
+ * arch/arm/src/efm32/efm32_rmu.h
+ *
+ * Copyright (C) 2015 Pierre-noel Bouteville . All rights reserved.
+ * Authors: Pierre-noel Bouteville <pnb990@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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_EFM32_EFM32_RMU_H
+#define __ARCH_ARM_SRC_EFM32_EFM32_RMU_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip/efm32_rmu.h"
+
+#ifdef CONFIG_EFM32_RMU
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+extern uint32_t g_efm32_rstcause;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+/************************************************************************************
+ * Name: efm32_rmu_initialize
+ *
+ * Description:
+ * Store reset cause into g_efm32_rstcause then clear reset cause register.
+ *
+ ************************************************************************************/
+
+void efm32_rmu_initialize(void);
+
+#endif /* CONFIG_EFM32_RMU */
+#endif /* __ARCH_ARM_SRC_EFM32_EFM32_RMU_H */