summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-18 20:24:20 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-18 20:24:20 +0000
commitd3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b (patch)
tree59cf90aba2d010904d3d3a8045b9d81f6866dbe6 /nuttx/arch/arm
parent31a5581021afca8240e6aa7eebed28ef7a55e561 (diff)
downloadpx4-nuttx-d3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b.tar.gz
px4-nuttx-d3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b.tar.bz2
px4-nuttx-d3aa6ce3315a4f75b5dabcc7358a34a1ce2e451b.zip
More files for the Cortex-M0/NUC120 port
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5659 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/armv6-m/nvic.h1
-rw-r--r--nuttx/arch/arm/src/nuc1xx/Make.defs5
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h10
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.c180
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.h93
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_gpio.c253
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_gpio.h209
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_idle.c187
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_irq.c398
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c115
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_lowputc.h87
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_start.c29
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c153
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_irq.c8
14 files changed, 1696 insertions, 32 deletions
diff --git a/nuttx/arch/arm/src/armv6-m/nvic.h b/nuttx/arch/arm/src/armv6-m/nvic.h
index 5d21c4666..c01d9421c 100644
--- a/nuttx/arch/arm/src/armv6-m/nvic.h
+++ b/nuttx/arch/arm/src/armv6-m/nvic.h
@@ -341,7 +341,6 @@
#define SYSTICK_CSR_CLKSOURCE (1 << 2) /* Bit 2: Selects the SysTick timer clock source */
#define SYSTICK_CSR_COUNTFLAG (1 << 16) /* Bit 16: Returns 1 if timer counted to 0 since
* the last read of this register */
-
/* SysTick reload value register */
#define SYSTICK_RVR_MASK (0x0fffffff) /* Bits 0-23 */
diff --git a/nuttx/arch/arm/src/nuc1xx/Make.defs b/nuttx/arch/arm/src/nuc1xx/Make.defs
index 38f5b3f6a..354152af8 100644
--- a/nuttx/arch/arm/src/nuc1xx/Make.defs
+++ b/nuttx/arch/arm/src/nuc1xx/Make.defs
@@ -38,7 +38,7 @@ HEAD_ASRC =
CMN_ASRCS = up_exception.S up_saveusercontext.S up_fullcontextrestore.S
CMN_ASRCS += up_switchcontext.S vfork.S
-CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c
CMN_CSRCS += up_createstack.c up_mdelay.c up_udelay.c up_exit.c
CMN_CSRCS += up_initialize.c up_initialstate.c up_interruptcontext.c
CMN_CSRCS += up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c
@@ -56,4 +56,5 @@ CMN_CSRCS += up_elf.c
endif
CHIP_ASRCS =
-CHIP_CSRCS = nuc_start.c
+CHIP_CSRCS = nuc_clockconfig.c nuc_gpio.c nuc_idle.c nuc_irq.c nuc_lowputc.c
+CHIP_CSRCS += nuc_start.c nuc_timerisr.c
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
index 4bc1b61f9..5ad806ea1 100644
--- a/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
@@ -421,14 +421,14 @@
/* GPIO port pin I/O mode control */
-#define GPIO_PMD_INPUT 0
-#define GPIO_PMD_OUTPUT 1
-#define GPIO_PMD_OPENDRAIN 2
-#define GPIO_PMD_BIDI 3
+#define GPIO_PMD_INPUT 0 /* Input */
+#define GPIO_PMD_OUTPUT 1 /* Push-pull output */
+#define GPIO_PMD_OPENDRAIN 2 /* Open drain output */
+#define GPIO_PMD_BIDI 3 /* Quasi bi-directional */
#define GPIO_PMD_SHIFT(n) ((n) << 1) /* Bits 2n-2n+_1: GPIOx Pin[n] mode control */
#define GPIO_PMD_MASK(n) (3 << GPIO_PMD_SHIFT(n))
-# define GPIO_PMD_MASK(n,v) ((v) << GPIO_PMD_SHIFT(n))
+# define GPIO_PMD(n,v) ((v) << GPIO_PMD_SHIFT(n))
#define GPIO_PMD0_SHIFT (0) /* Bits 0-1: GPIOx Pin0 mode control */
#define GPIO_PMD0_MASK (3 << GPIO_PMD0_SHIFT)
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.c b/nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.c
new file mode 100644
index 000000000..b89d9e036
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.c
@@ -0,0 +1,180 @@
+/****************************************************************************
+ * arch/arm/src/nuc1xx/nuc_clockconfig.c
+ *
+ * Copyright (C) 2013 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 <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "chip/chip/nuc_gcr.h"
+#include "chip/chip/nuc_clk.h"
+
+#include "nuc_clockconfig.h"
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nuc_unlock
+ *
+ * Description:
+ * Unlock registers
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void nuc_unlock(void)
+{
+ putreg32(0x59, NUC_GCR_REGWRPROT);
+ putreg32(0x16, NUC_GCR_REGWRPROT);
+ putreg32(0x88, NUC_GCR_REGWRPROT);
+}
+
+/****************************************************************************
+ * Name: nuclock
+ *
+ * Description:
+ * Lok registers
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void nuc_lock(void)
+{
+ putreg32(0, NUC_GCR_REGWRPROT);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/************************************************************************************
+ * Name: nuc_clockconfig
+ *
+ * Description:
+ * Called to establish the clock settings based on the values in board.h.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
+
+void nuc_clockconfig(void)
+{
+ uint32_t regval;
+
+ /* Unlock registers */
+
+ nuc_unlock();
+
+ /* Enable External 4~24 mhz high speed crystal */
+
+ regval = getreg32(NUC_CLK_PWRCON);
+ regval |= CLK_PWRCON_XTL12M_EN;
+ putreg32(regval, NUC_CLK_PWRCON);
+
+ /* Delay to assure that crystal input to be stable */
+
+ up_mdelay(5);
+
+ /* Set up the PLL configuration.
+ *
+ * Feedback divider (FB_DV) = Determined by settings in board.h
+ * Input divider (IN_DV) = Determined by settings in board.h
+ * Output divider (OUT_DV) = Determined by settings in board.h
+ * Power down mode (PD) = Normal mode (0)
+ * Bypass (BP) = Normal mode (0)
+ * FOUT enable (OE) = PLL FOUT enabled (0)
+ * PLL srouce clock (PLL_SRC) = External high speed crystal (0)
+ */
+
+ regval = getreg32(NUC_CLK_PLLCON);
+ regval &= ~(CLK_PLLCON_FB_DV_MASK | CLK_PLLCON_IN_DV_MASK |
+ CLK_PLLCON_OUT_DV_MASK | CLK_PLLCON_PD | CLK_PLLCON_BP |
+ CLK_PLLCON_OE | CLK_PLLCON_PLL_SRC);
+ regval |= (CLK_PLLCON_FB_DV(BOARD_PLL_FB_DV) |
+ CLK_PLLCON_IN_DV(BOARD_PLL_IN_DV) |
+ CLK_PLLCON_OUT_DV(BOARD_PLL_OUT_DV));
+ putreg32(regval, NUC_CLK_PLLCON);
+
+ /* Delay until the PLL output is stable */
+
+ up_mdelay(5);
+
+ /* Set the HCLK divider per settings from the board.h file */
+
+ regval = getreg32(NUC_CLK_CLKDIV);
+ regval &= ~CLK_CLKDIV_HCLK_N_MASK;
+ regval |= CLK_CLKDIV_HCLK_N(BOARD_HCLK_N);
+ putreg32(regval, NUC_CLK_CLKDIV);
+
+ /* Select the PLL output as the HCLKC source */
+
+ regval = getreg32(NUC_CLK_CLKSEL0);
+ regval &= ~CLK_CLKSEL0_HCLK_S_MASK;
+ regval |= CLK_CLKSEL0_HCLK_S_PLL;
+ putreg32(regval, NUC_CLK_CLKSEL0);
+ up_mdelay(1);
+
+ /* Lock the registers */
+
+ nuc_lock();
+}
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.h b/nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.h
new file mode 100644
index 000000000..aaff547cf
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_clockconfig.h
@@ -0,0 +1,93 @@
+/************************************************************************************
+ * arch/arm/src/nuc1xx/nuc_clockconfig.h
+ *
+ * Copyright (C) 2013 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_NUC1XX_NUC_CLOCKCONFIG_H
+#define __ARCH_ARM_SRC_NUC1XX_NUC_CLOCKCONFIG_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: nuc_clockconfig
+ *
+ * Description:
+ * Called to establish the clock settings based on the values in board.h.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
+
+void nuc_clockconfig(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_NUC1XX_NUC_CLOCKCONFIG_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.c b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.c
new file mode 100644
index 000000000..be5919157
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.c
@@ -0,0 +1,253 @@
+/****************************************************************************
+ * arch/arm/src/nuc1xx/nuc_gpio.c
+ *
+ * Copyright (C) 2013 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 <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "chip/nuc_gpio.h"
+
+#include "nuc_gpio.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nuc_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ * Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...)
+ * function, it must be unconfigured with nuc_unconfiggpio() with
+ * the same cfgset first before it can be set to non-alternative function.
+ *
+ * Returns:
+ * OK on success
+ * ERROR on invalid port, or when pin is locked as ALT function.
+ *
+ ****************************************************************************/
+
+int nuc_configgpio(gpio_cfgset_t cfgset)
+{
+ uintptr_t base;
+ uint32_t regaddr;
+ uint32_t regval;
+ uint32_t isrc;
+ uint32_t imd;
+ uint32_t ien;
+ uint32_t value;
+ int port;
+ int pin;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = (cfgset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+
+ DEBUGASSERT((unsigned)port <= NUC_GPIO_PORTE);
+ base = NUC_GPIO_CTRL_BASE(port);
+
+ /* Set the the GPIO PMD register */
+
+ regaddr = base + NUC_GPIOA_PMD_OFFSET;
+ regval = getreg32(regaddr);
+ regval &= ~GPIO_PMD_MASK(pin);
+
+ switch (cfgset & GPIO_MODE_MASK)
+ {
+ default:
+ case GPIO_INPUT: /* Input */
+ value = GPIO_PMD_INPUT;
+ break;
+
+ case GPIO_OUTPUT: /* Push-pull output */
+ value = GPIO_PMD_OUTPUT;
+ break;
+
+ case GPIO_OPENDRAIN: /* Open drain output */
+ value = GPIO_PMD_OPENDRAIN;
+ break;
+
+ case GPIO_BIDI: /* Quasi bi-directional */
+ value = GPIO_PMD_BIDI;
+ break;
+ }
+
+ regval |= GPIO_PMD(pin, value);
+ putreg32(regval, regaddr);
+
+ /* Check if we need to disable the digital input path */
+
+ regaddr = base + NUC_GPIO_OFFD_OFFSET;
+ regval = getreg32(regaddr);
+ regval &= ~GPIO_OFFD(pin);
+
+ if ((cfgset & GPIO_ANALOG) != 0)
+ {
+ regval |= GPIO_OFFD(pin);
+ }
+
+ putreg32(regval, regaddr);
+
+ /* Check if we need to enable debouncing */
+
+ regaddr = base + NUC_GPIO_DBEN_OFFSET;
+ regval = getreg32(regaddr);
+ regval &= ~GPIO_DBEN(pin);
+
+ if ((cfgset & GPIO_DEBOUNCE) != 0)
+ {
+ regval |= GPIO_DBEN(pin);
+ }
+
+ putreg32(regval, regaddr);
+
+ /* Configure interrupting pins */
+
+ isrc = getreg32(base + NUC_GPIO_ISRC_OFFSET);
+ isrc &= ~GPIO_ISRC(pin);
+
+ imd = getreg32(base + NUC_GPIO_IMD_OFFSET);
+ imd &= ~GPIO_IMD(pin);
+
+ ien = getreg32(base + NUC_GPIO_IEN_OFFSET);
+ ien &= ~(GPIO_IF_EN(pin) | GPIO_IR_EN(pin));
+
+ switch (cfgset & GPIO_INTERRUPT_MASK)
+ {
+ case GPIO_INTERRUPT_RISING_EDGE:
+ isrc |= GPIO_ISRC(pin);
+ ien |= GPIO_IR_EN(pin);
+ break;
+
+ case GPIO_INTERRUPT_FALLING_EDGE:
+ isrc |= GPIO_ISRC(pin);
+ ien |= GPIO_IF_EN(pin);
+ break;
+
+ case GPIO_INTERRUPT_BOTH_EDGES:
+ isrc |= GPIO_ISRC(pin);
+ ien |= (GPIO_IF_EN(pin) | GPIO_IR_EN(pin));
+ break;
+
+ case GPIO_INTERRUPT_HIGH_LEVEL:
+ isrc |= GPIO_ISRC(pin);
+ imd |= GPIO_IMD(pin);
+ ien |= GPIO_IR_EN(pin);
+ break;
+
+ case GPIO_INTERRUPT_LOW_LEVEL:
+ isrc |= GPIO_ISRC(pin);
+ imd |= GPIO_IMD(pin);
+ ien |= GPIO_IF_EN(pin);
+ break;
+
+ default:
+ break;
+ }
+
+ putreg32(ien, base + NUC_GPIO_IEN_OFFSET);
+ putreg32(imd, base + NUC_GPIO_IMD_OFFSET);
+ putreg32(isrc, base + NUC_GPIO_ISRC_OFFSET);
+ return 0;
+}
+
+/****************************************************************************
+ * Name: nuc_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ****************************************************************************/
+
+void nuc_gpiowrite(gpio_cfgset_t pinset, bool value)
+{
+ int port;
+ int pin;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+
+ DEBUGASSERT((unsigned)port <= NUC_GPIO_PORTE);
+ putreg32((uint32_t)value, NUC_PORT_PDIO(port, pin));
+}
+
+/****************************************************************************
+ * Name: nuc_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ****************************************************************************/
+
+bool nuc_gpioread(gpio_cfgset_t pinset)
+{
+ int port;
+ int pin;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
+
+ DEBUGASSERT((unsigned)port <= NUC_GPIO_PORTE);
+ return (getreg32(NUC_PORT_PDIO(port, pin)) & PORT_MASK) != 0;
+}
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
index b251ddbe6..7da42af8f 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
@@ -1,4 +1,4 @@
-/********************************************************************************************
+/****************************************************************************
* arch/arm/src/nuc1xx/nuc_gpio.h
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
@@ -31,34 +31,213 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ********************************************************************************************/
+ ****************************************************************************/
#ifndef __ARCH_ARM_SRC_NUC1XX_NUC_GPIO_H
#define __ARCH_ARM_SRC_NUC1XX_NUC_GPIO_H
-/********************************************************************************************
+/****************************************************************************
* Included Files
- ********************************************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+# include <stdbool.h>
+#endif
+
+#include <nuttx/irq.h>
+
#include "chip.h"
-#include "chip/chip/nuc_gpio.h"
+#include "chip/nuc_gpio.h"
+
+/****************************************************************************
+ * Pre-processor Declarations
+ ****************************************************************************/
+
+/* Bit-encoded input to nuc_configgpio() */
+
+/* 16-bit Encoding:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * MMAD III. VPPP BBBB
+ */
+
+/* GPIO mode:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * MM.. .... .... ....
+ */
+
+#define GPIO_MODE_SHIFT (14) /* Bits 145_15: GPIO mode */
+#define GPIO_MODE_MASK (3 << GPIO_MODE_SHIFT)
+# define GPIO_INPUT (0 << GPIO_MODE_SHIFT) /* Input */
+# define GPIO_OUTPUT (1 << GPIO_MODE_SHIFT) /* Push-pull output */
+# define GPIO_OPENDRAIN (2 << GPIO_MODE_SHIFT) /* Open drain output */
+# define GPIO_BIDI (3 << GPIO_MODE_SHIFT) /* Quasi bi-directional */
+
+/* GPIO analog: If the pin is an analog input, then it would be necessary to
+ * disable the digital input
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * ..A. .... .... ....
+ */
+
+#define GPIO_ANALOG (1 << 13) /* Bit 13: Disable digital input */
+
+/* De-bounce enable:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * ...D .... .... ....
+ */
+
+#define GPIO_DEBOUNCE (1 << 12) /* Bit 12: Debounce enable */
+
+/* Interrupt Controls:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... III. .... ....
+ */
+
+#define GPIO_INTERRUPT_SHIFT (9) /* Bits 9-11: Interrupt controls */
+#define GPIO_INTERRUPT_MASK (7 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_NONE (0 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_RISING_EDGE (1 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_FALLING_EDGE (2 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_BOTH_EDGES (3 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_HIGH_LEVEL (4 << GPIO_INTERRUPT_SHIFT)
+# define GPIO_INTERRUPT_LOW_LEVEL (5 << GPIO_INTERRUPT_SHIFT)
+
+/* If the pin is a GPIO digital output, then this identifies the initial output value.
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... .... V... ....
+ */
+
+#define GPIO_OUTPUT_SET (1 << 7) /* Bit 7: If output, inital value of output */
+#define GPIO_OUTPUT_CLEAR (0)
-/********************************************************************************************
- * Pre-processor Definitions
- ********************************************************************************************/
+/* This identifies the GPIO port:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... .... .PPP ....
+ */
+
+#define GPIO_PORT_SHIFT 4 /* Bit 4-6: Port number */
+#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
+# define GPIO_PORTA (0 << GPIO_PORT_SHIFT) /* GPIOA */
+# define GPIO_PORTB (1 << GPIO_PORT_SHIFT) /* GPIOB */
+# define GPIO_PORTC (2 << GPIO_PORT_SHIFT) /* GPIOC */
+# define GPIO_PORTD (3 << GPIO_PORT_SHIFT) /* GPIOD */
+# define GPIO_PORTE (4 << GPIO_PORT_SHIFT) /* GPIOE */
+#
+/* This identifies the bit in the port:
+ *
+ * 1111 1100 0000 0000
+ * 5432 1098 7654 3210
+ * ---- ---- ---- ----
+ * .... .... .... BBBB
+ */
-/********************************************************************************************
+#define GPIO_PIN_SHIFT 0 /* Bits 0-3: GPIO number: 0-15 */
+#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT)
+# define GPIO_PIN0 (0 << GPIO_PIN_SHIFT)
+# define GPIO_PIN1 (1 << GPIO_PIN_SHIFT)
+# define GPIO_PIN2 (2 << GPIO_PIN_SHIFT)
+# define GPIO_PIN3 (3 << GPIO_PIN_SHIFT)
+# define GPIO_PIN4 (4 << GPIO_PIN_SHIFT)
+# define GPIO_PIN5 (5 << GPIO_PIN_SHIFT)
+# define GPIO_PIN6 (6 << GPIO_PIN_SHIFT)
+# define GPIO_PIN7 (7 << GPIO_PIN_SHIFT)
+# define GPIO_PIN8 (8 << GPIO_PIN_SHIFT)
+# define GPIO_PIN9 (9 << GPIO_PIN_SHIFT)
+# define GPIO_PIN10 (10 << GPIO_PIN_SHIFT)
+# define GPIO_PIN11 (11 << GPIO_PIN_SHIFT)
+# define GPIO_PIN12 (12 << GPIO_PIN_SHIFT)
+# define GPIO_PIN13 (13 << GPIO_PIN_SHIFT)
+# define GPIO_PIN14 (14 << GPIO_PIN_SHIFT)
+# define GPIO_PIN15 (15 << GPIO_PIN_SHIFT)
+
+/****************************************************************************
* Public Types
- ********************************************************************************************/
+ ****************************************************************************/
+
+typedef uint16_t gpio_cfgset_t;
-/********************************************************************************************
+/****************************************************************************
* Public Data
- ********************************************************************************************/
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nuc_configgpio
+ *
+ * Description:
+ * Configure a GPIO pin based on bit-encoded description of the pin.
+ * Once it is configured as Alternative (GPIO_ALT|GPIO_CNF_AFPP|...)
+ * function, it must be unconfigured with nuc_unconfiggpio() with
+ * the same cfgset first before it can be set to non-alternative function.
+ *
+ * Returns:
+ * OK on success
+ * ERROR on invalid port, or when pin is locked as ALT function.
+ *
+ ****************************************************************************/
+
+int nuc_configgpio(gpio_cfgset_t cfgset);
+
+/****************************************************************************
+ * Name: nuc_gpiowrite
+ *
+ * Description:
+ * Write one or zero to the selected GPIO pin
+ *
+ ****************************************************************************/
+
+void nuc_gpiowrite(gpio_cfgset_t pinset, bool value);
+
+/****************************************************************************
+ * Name: nuc_gpioread
+ *
+ * Description:
+ * Read one or zero from the selected GPIO pin
+ *
+ ****************************************************************************/
+
+bool nuc_gpioread(gpio_cfgset_t pinset);
-/********************************************************************************************
- * Public Functions
- ********************************************************************************************/
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_NUC1XX_NUC_GPIO_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_idle.c b/nuttx/arch/arm/src/nuc1xx/nuc_idle.c
new file mode 100644
index 000000000..3c7fc53da
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_idle.c
@@ -0,0 +1,187 @@
+/****************************************************************************
+ * arch/arm/src/stm32/nuc_idle.c
+ *
+ * Copyright (C) 2013 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 <arch/board/board.h>
+#include <nuttx/config.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/power/pm.h>
+
+#include <arch/irq.h>
+
+#include "chip.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Does the board support an IDLE LED to indicate that the board is in the
+ * IDLE state?
+ */
+
+#if defined(CONFIG_ARCH_LEDS) && defined(LED_IDLE)
+# define BEGIN_IDLE() up_ledon(LED_IDLE)
+# define END_IDLE() up_ledoff(LED_IDLE)
+#else
+# define BEGIN_IDLE()
+# define END_IDLE()
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idlepm
+ *
+ * Description:
+ * Perform IDLE state power management.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void up_idlepm(void)
+{
+ static enum pm_state_e oldstate = PM_NORMAL;
+ enum pm_state_e newstate;
+ irqstate_t flags;
+ int ret;
+
+ /* Decide, which power saving level can be obtained */
+
+ newstate = pm_checkstate();
+
+ /* Check for state changes */
+
+ if (newstate != oldstate)
+ {
+ flags = irqsave();
+
+ /* Perform board-specific, state-dependent logic here */
+
+ llvdbg("newstate= %d oldstate=%d\n", newstate, oldstate);
+
+ /* Then force the global state change */
+
+ ret = pm_changestate(newstate);
+ if (ret < 0)
+ {
+ /* The new state change failed, revert to the preceding state */
+
+ (void)pm_changestate(oldstate);
+ }
+ else
+ {
+ /* Save the new state */
+
+ oldstate = newstate;
+ }
+
+ /* MCU-specific power management logic */
+
+ switch (newstate)
+ {
+ case PM_NORMAL:
+ break;
+
+ case PM_IDLE:
+ break;
+
+ case PM_STANDBY:
+ nuc_pmstop(true);
+ break;
+
+ case PM_SLEEP:
+ (void)nuc_pmstandby();
+ break;
+
+ default:
+ break;
+ }
+
+ irqrestore(flags);
+ }
+}
+#else
+# define up_idlepm()
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_idle
+ *
+ * Description:
+ * up_idle() is the logic that will be executed when their is no other
+ * ready-to-run task. This is processor idle time and will continue until
+ * some interrupt occurs to cause a context switch from the idle task.
+ *
+ * Processing in this state may be processor-specific. e.g., this is where
+ * power management operations might be performed.
+ *
+ ****************************************************************************/
+
+void up_idle(void)
+{
+#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS)
+ /* If the system is idle and there are no timer interrupts, then process
+ * "fake" timer interrupts. Hopefully, something will wake up.
+ */
+
+ sched_process_timer();
+#else
+
+ /* Perform IDLE mode power management */
+
+ up_idlepm();
+
+ /* Sleep until an interrupt occurs to save power. */
+
+ BEGIN_IDLE();
+ asm("WFI");
+ END_IDLE();
+#endif
+}
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_irq.c b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
new file mode 100644
index 000000000..62c17e1a9
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_irq.c
@@ -0,0 +1,398 @@
+/****************************************************************************
+ * arch/arm/src/stm32/nuc_irq.c
+ * arch/arm/src/chip/nuc_irq.c
+ *
+ * Copyright (C) 2009-2013 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 <stdint.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <arch/irq.h>
+
+#include "nvic.h"
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Get a 32-bit version of the default priority */
+
+#define DEFPRIORITY32 \
+ (NVIC_SYSH_PRIORITY_DEFAULT << 24 | NVIC_SYSH_PRIORITY_DEFAULT << 16 |\
+ NVIC_SYSH_PRIORITY_DEFAULT << 8 | NVIC_SYSH_PRIORITY_DEFAULT)
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+volatile uint32_t *current_regs;
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nuc_dumpnvic
+ *
+ * Description:
+ * Dump some interesting NVIC registers
+ *
+ ****************************************************************************/
+
+#if defined(CONFIG_DEBUG_IRQ) && defined (CONFIG_DEBUG)
+static void nuc_dumpnvic(const char *msg, int irq)
+{
+ irqstate_t flags;
+
+ flags = irqsave();
+
+ slldbg("NVIC (%s, irq=%d):\n", msg, irq);
+ slldbg(" ISER: %08x ICER: %08x\n",
+ getreg32(ARMV6M_NVIC_ISER), getreg32(ARMV6M_NVIC_ICER));
+ slldbg(" ISPR: %08x ICPR: %08x\n",
+ getreg32(ARMV6M_NVIC_ISPR), getreg32(ARMV6M_NVIC_ICPR));
+ slldbg(" IRQ PRIO: %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR0), getreg32(ARMV6M_NVIC_IPR1),
+ getreg32(ARMV6M_NVIC_IPR2), getreg32(ARMV6M_NVIC_IPR3));
+ slldbg(" %08x %08x %08x %08x\n",
+ getreg32(ARMV6M_NVIC_IPR4), getreg32(ARMV6M_NVIC_IPR5),
+ getreg32(ARMV6M_NVIC_IPR6), getreg32(ARMV6M_NVIC_IPR7));
+
+ slldbg("SYSCON:\n");
+ slldbg(" CPUID: %08x\n",
+ getreg32(ARMV6M_SYSCON_CPUID));
+ slldbg(" ICSR: %08x AIRCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_ICSR), getreg32(ARMV6M_SYSCON_AIRCR));
+ slldbg(" SCR: %08x CCR: %08x\n",
+ getreg32(ARMV6M_SYSCON_SCR), getreg32(ARMV6M_SYSCON_CCR));
+ slldbg(" SHPR2: %08x SHPR3: %08x\n",
+ getreg32(ARMV6M_SYSCON_SHPR2), getreg32(ARMV6M_SYSCON_SHPR3));
+
+ irqrestore(flags);
+}
+
+#else
+# define nuc_dumpnvic(msg, irq)
+#endif
+
+/****************************************************************************
+ * Name: nuc_nmi, nuc_busfault, nuc_usagefault, nuc_pendsv,
+ * nuc_dbgmonitor, nuc_pendsv, nuc_reserved
+ *
+ * Description:
+ * Handlers for various execptions. None are handled and all are fatal
+ * error conditions. The only advantage these provided over the default
+ * unexpected interrupt handler is that they provide a diagnostic output.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+static int nuc_nmi(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! NMI received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+static int nuc_pendsv(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! PendSV received\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+
+static int nuc_reserved(int irq, FAR void *context)
+{
+ (void)irqsave();
+ dbg("PANIC!!! Reserved interrupt\n");
+ PANIC(OSERR_UNEXPECTEDISR);
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Name: nuc_prioritize_syscall
+ *
+ * Description:
+ * Set the priority of an exception. This function may be needed
+ * internally even if support for prioritized interrupts is not enabled.
+ *
+ ****************************************************************************/
+
+static inline void nuc_prioritize_syscall(int priority)
+{
+ uint32_t regval;
+
+ /* SVCALL is system handler 11 */
+
+ regval = getreg32(ARMV6M_SYSCON_SHPR2);
+ regval &= ~SYSCON_SHPR2_PRI_11_MASK;
+ regval |= (priority << SYSCON_SHPR2_PRI_11_SHIFT);
+ putreg32(regval, ARMV6M_SYSCON_SHPR2);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_irqinitialize
+ ****************************************************************************/
+
+void up_irqinitialize(void)
+{
+ uint32_t regaddr;
+ int i;
+
+ /* Disable all interrupts */
+
+ putreg32(0xffffffff, ARMV6M_NVIC_ICER);
+
+ /* Set all interrupts (and exceptions) to the default priority */
+
+ putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR2);
+ putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3);
+ putreg32(DEFPRIORITY32, ARMV6M_SYSCON_SHPR3);
+
+ /* Now set all of the interrupt lines to the default priority */
+
+ for (i = 0; i < 8; i++)
+ {
+ regaddr = ARMV6M_NVIC_IPR(i);
+ putreg32(DEFPRIORITY32, regaddr);
+ }
+
+ /* currents_regs is non-NULL only while processing an interrupt */
+
+ current_regs = NULL;
+
+ /* Attach the SVCall and Hard Fault exception handlers. The SVCall
+ * exception is used for performing context switches; The Hard Fault
+ * must also be caught because a SVCall may show up as a Hard Fault
+ * under certain conditions.
+ */
+
+ irq_attach(NUC_IRQ_SVCALL, up_svcall);
+ irq_attach(NUC_IRQ_HARDFAULT, up_hardfault);
+
+ /* Set the priority of the SVCall interrupt */
+
+#ifdef CONFIG_ARCH_IRQPRIO
+/* up_prioritize_irq(NUC_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); */
+#endif
+ nuc_prioritize_syscall(NVIC_SYSH_SVCALL_PRIORITY);
+
+ /* Attach all other processor exceptions (except reset and sys tick) */
+
+#ifdef CONFIG_DEBUG
+ irq_attach(NUC_IRQ_NMI, nuc_nmi);
+ irq_attach(NUC_IRQ_PENDSV, nuc_pendsv);
+ irq_attach(NUC_IRQ_RESERVED, nuc_reserved);
+#endif
+
+ nuc_dumpnvic("initial", NR_IRQS);
+
+#ifndef CONFIG_SUPPRESS_INTERRUPTS
+
+ /* And finally, enable interrupts */
+
+ irqenable();
+#endif
+}
+
+/****************************************************************************
+ * Name: up_disable_irq
+ *
+ * Description:
+ * Disable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_disable_irq(int irq)
+{
+ DEBUGASSERT(irq == NUC_IRQ_SYSTICK ||
+ (irq >= NUC_IRQ_INTERRUPT && irq < NR_IRQS));
+
+ /* Check for an external interrupt */
+
+ if (irq >= NUC_IRQ_INTERRUPT && irq < NUC_IRQ_INTERRUPT + 32)
+ {
+ /* Set the appropriate bit in the ICER register to disable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - NUC_IRQ_INTERRUPT)), ARMV6M_NVIC_ICER);
+ }
+
+ /* Handle processor exceptions. Only SysTick can be disabled */
+
+ else if (irq == NUC_IRQ_SYSTICK)
+ {
+ modifyreg32(ARMV6M_SYSTICK_CSR, SYSTICK_CSR_ENABLE, 0);
+ }
+
+ nuc_dumpnvic("disable", irq);
+}
+
+/****************************************************************************
+ * Name: up_enable_irq
+ *
+ * Description:
+ * Enable the IRQ specified by 'irq'
+ *
+ ****************************************************************************/
+
+void up_enable_irq(int irq)
+{
+ DEBUGASSERT(irq == NUC_IRQ_SYSTICK ||
+ (irq >= NUC_IRQ_INTERRUPT && irq < NR_IRQS));
+
+ /* Check for external interrupt */
+
+ if (irq >= NUC_IRQ_INTERRUPT && irq < NUC_IRQ_INTERRUPT + 32)
+ {
+ /* Set the appropriate bit in the ISER register to enable the
+ * interrupt
+ */
+
+ putreg32((1 << (irq - NUC_IRQ_INTERRUPT)), ARMV6M_NVIC_ISER);
+ }
+
+ /* Handle processor exceptions. Only SysTick can be disabled */
+
+ else if (irq == NUC_IRQ_SYSTICK)
+ {
+ modifyreg32(ARMV6M_SYSTICK_CSR, 0, SYSTICK_CSR_ENABLE);
+ }
+
+ nuc_dumpnvic("enable", irq);
+}
+
+/****************************************************************************
+ * Name: up_maskack_irq
+ *
+ * Description:
+ * Mask the IRQ and acknowledge it
+ *
+ ****************************************************************************/
+
+void up_maskack_irq(int irq)
+{
+ up_disable_irq(irq);
+}
+
+/****************************************************************************
+ * Name: up_prioritize_irq
+ *
+ * Description:
+ * Set the priority of an IRQ.
+ *
+ * Since this API is not supported on all architectures, it should be
+ * avoided in common implementations where possible.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQPRIO
+int up_prioritize_irq(int irq, int priority)
+{
+ uint32_t regaddr;
+ uint32_t regval;
+ int shift;
+
+ DEBUGASSERT(irq == NUC_IRQ_SVCALL ||
+ irq == NUC_IRQ_PENDSV ||
+ irq == NUC_IRQ_SYSTICK ||
+ (irq >= NUC_IRQ_INTERRUPT && irq < NR_IRQS));
+ DEBUGASSERT(priority >= NVIC_SYSH_DISABLE_PRIORITY &&
+ priority <= NVIC_SYSH_PRIORITY_MIN);
+
+ /* Check for external interrupt */
+
+ if (irq >= NUC_IRQ_INTERRUPT && irq < NUC_IRQ_INTERRUPT + 32)
+ {
+ /* ARMV6M_NVIC_IPR() maps register IPR0-IPR7 with four settings per
+ * register.
+ */
+
+ regaddr = ARMV6M_NVIC_IPR(irq >> 2);
+ shift = (irq & 3) << 3;
+ }
+
+ /* Handle processor exceptions. Only SVCall, PendSV, and SysTick can be
+ * reprioritized. And we will not permit modification of SVCall through
+ * this function.
+ */
+
+ else if (irq == NUC_IRQ_PENDSV)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_14_SHIFT;
+ }
+ else if (irq == NUC_IRQ_SYSTICK)
+ {
+ regaddr = ARMV6M_SYSCON_SHPR2;
+ shift = SYSCON_SHPR3_PRI_15_SHIFT;
+ }
+ else
+ {
+ return ERROR;
+ }
+
+ /* Set the priority */
+
+ regval = getreg32(regaddr);
+ regval &= ~((uint32_t)0xff << shift);
+ regval |= ((uint32_t)priority << shift);
+ putreg32(regval, regaddr);
+
+ nuc_dumpnvic("prioritize", irq);
+ return OK;
+}
+#endif
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c
new file mode 100644
index 000000000..7d8509feb
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c
@@ -0,0 +1,115 @@
+/****************************************************************************
+ * arch/arm/src/nuc1xx/nuc_lowputc.c
+ *
+ * Copyright (C) 2013 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 <stdint.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "nuc_config.h"
+#include "chip/chip/nuc_clk.h"
+#include "chip/chip/nuc_uart.h"
+
+#include "nuc_lowputc.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Here we assume that the default clock source for the UART modules is
+ * the external high speed crystal.
+ */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nuc_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization.
+ *
+ *****************************************************************************/
+
+void nuc_lowsetup(void)
+{
+#ifdef HAVE_UART
+ uint32_t regval;
+
+ /* Configure the UART clock source
+ *
+ * Here we assume that the UART clock source is the external high speed
+ * crystal -- the power on default value in the CLKSEL0 register.
+ */
+
+ /* Enable UART clocking for the selected UARTs */
+
+ regval = getreg32(NUC_CLK_APBCLK);
+ regval &= ~(CLK_APBCLK_UART0_EN | CLK_APBCLK_UART1_EN | CLK_APBCLK_UART2_EN);
+
+#ifdef CONFIG_NUC_UART0
+ regval |= CLK_APBCLK_UART0_EN;
+#endif
+#ifdef CONFIG_NUC_UART1
+ regval |= CLK_APBCLK_UART1_EN;
+#endif
+#ifdef CONFIG_NUC_UART2
+ regval |= CLK_APBCLK_UART2_EN;
+#endif
+
+ putreg32(regval, NUC_CLK_APBCLK);
+
+ /* Configure UART GPIO pins */
+#warning "Missing logic"
+
+ /* Configure the console UART */
+#warning "Missing logic"
+
+#endif /* HAVE_UART */
+} \ No newline at end of file
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.h b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.h
new file mode 100644
index 000000000..7561895c5
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.h
@@ -0,0 +1,87 @@
+/************************************************************************************
+ * arch/arm/src/nuc1xx/nuc_lowputc.h
+ *
+ * Copyright (C) 2013 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_NUC1XX_NUC_LOWPUTC_H
+#define __ARCH_ARM_SRC_NUC1XX_NUC_LOWPUTC_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: nuc_lowsetup
+ *
+ * Description:
+ * Called at the very beginning of _start. Performs low level initialization.
+ *
+ ************************************************************************************/
+
+void nuc_lowsetup(void);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_ARM_SRC_NUC1XX_NUC_LOWPUTC_H */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_start.c b/nuttx/arch/arm/src/nuc1xx/nuc_start.c
index 767e959b4..cd410db27 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_start.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_start.c
@@ -50,7 +50,33 @@
#include "up_arch.h"
#include "up_internal.h"
-#include "nuc_gpio.h"
+#include "nuc_lowputc.h"
+#include "nuc_clockconfig.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Memory Map:
+ *
+ * 0x0000:0000 - Beginning of FLASH. Address of exception vectors.
+ * 0x0001:ffff - End of flash (assuming 128KB of FLASH)
+ * 0x2000:0000 - Start of SRAM and start of .data (_sdata)
+ * - End of .data (_edata) abd start of .bss (_sbss)
+ * - End of .bss (_ebss) and bottom of idle stack
+ * - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack,
+ * start of heap
+ * 0x2000:3fff - End of SRAM and end of heap (assuming 16KB of SRAM)
+ */
+
+#define IDLE_STACK ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+#define HEAP_BASE ((uint32_t)&_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+const uint32_t g_heapbase = HEAP_BASE;
/****************************************************************************
* Private Functions
@@ -91,7 +117,6 @@ void __start(void)
nuc_clockconfig();
nuc_lowsetup();
- nuc_gpioinit();
showprogress('A');
/* Clear .bss. We'll do this inline (vs. calling memset) just to be
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c b/nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c
new file mode 100644
index 000000000..c27474601
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_timerisr.c
@@ -0,0 +1,153 @@
+/****************************************************************************
+ * arch/arm/src/nuc1xx/nuc_timerisr.c
+ *
+ * Copyright (C) 2013 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 <stdint.h>
+#include <time.h>
+#include <debug.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include "nvic.h"
+#include "clock_internal.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "chip.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* The desired timer interrupt frequency is provided by the definition
+ * CLK_TCK (see include/time.h). CLK_TCK defines the desired number of
+ * system clock ticks per second. That value is a user configurable setting
+ * that defaults to 100 (100 ticks per second = 10 MS interval).
+ *
+ * Here we assume that the default clock source for the SysTick is the
+ * external high speed crystal -- the power-on default value for the
+ * CLKSEL0 register
+ *
+ * Then, for example, if BOARD_HIGHSPEED_XTAL_FREQUENCY is 12MHz and
+ * CLK_TCK is 100, the the reload value would be:
+ *
+ * SYSTICK_RELOAD = (12,000,000 / 100) - 1
+ * = 119,999
+ * = 0x1d4bf
+ *
+ * Which fits within the maximum 14-bit reload value.
+ */
+
+#define SYSTICK_RELOAD ((BOARD_HIGHSPEED_XTAL_FREQUENCY / CLK_TCK) - 1)
+
+/* The size of the reload field is 24 bits. Verify that the reload value
+ * will fit in the reload register.
+ */
+
+#if SYSTICK_RELOAD > 0x00ffffff
+# error SYSTICK_RELOAD exceeds the range of the RELOAD register
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: up_timerisr
+ *
+ * Description:
+ * The timer ISR will perform a variety of services for various portions
+ * of the systems.
+ *
+ ****************************************************************************/
+
+int up_timerisr(int irq, uint32_t *regs)
+{
+ /* Process timer interrupt */
+
+ sched_process_timer();
+ return 0;
+}
+
+/****************************************************************************
+ * Function: up_timerinit
+ *
+ * Description:
+ * This function is called during start-up to initialize
+ * the timer interrupt.
+ *
+ ****************************************************************************/
+
+void up_timerinit(void)
+{
+ uint32_t regval;
+
+ /* Set the SysTick interrupt to the default priority */
+
+ regval = getreg32(ARMV6M_SYSCON_SHPR3);
+ regval &= ~SYSCON_SHPR3_PRI_15_MASK;
+ regval |= (NVIC_SYSH_PRIORITY_DEFAULT << SYSCON_SHPR3_PRI_15_SHIFT);
+ putreg32(regval, ARMV6M_SYSCON_SHPR3);
+
+ /* Configure SysTick to interrupt at the requested rate */
+
+ putreg32(SYSTICK_RELOAD, ARMV6M_SYSTICK_RVR);
+
+ /* Attach the timer interrupt vector */
+
+ (void)irq_attach(NUC_IRQ_SYSTICK, (xcpt_t)up_timerisr);
+
+ /* Enable SysTick interrupts */
+
+ putreg32((SYSTICK_CSR_CLKSOURCE | SYSTICK_CSR_TICKINT | SYSTICK_CSR_ENABLE),
+ ARMV6M_SYSTICK_CSR);
+
+ /* And enable the timer interrupt */
+
+ up_enable_irq(NUC_IRQ_SYSTICK);
+}
diff --git a/nuttx/arch/arm/src/stm32/stm32_irq.c b/nuttx/arch/arm/src/stm32/stm32_irq.c
index 92117e983..79b8120e9 100644
--- a/nuttx/arch/arm/src/stm32/stm32_irq.c
+++ b/nuttx/arch/arm/src/stm32/stm32_irq.c
@@ -57,12 +57,6 @@
* Definitions
****************************************************************************/
-/* Enable NVIC debug features that are probably only desireable during
- * bringup
- */
-
-#undef STM32_IRQ_DEBUG
-
/* Get a 32-bit version of the default priority */
#define DEFPRIORITY32 \
@@ -93,7 +87,7 @@ volatile uint32_t *current_regs;
*
****************************************************************************/
-#if defined(STM32_IRQ_DEBUG) && defined (CONFIG_DEBUG)
+#if defined(CONFIG_DEBUG_IRQ) && defined (CONFIG_DEBUG)
static void stm32_dumpnvic(const char *msg, int irq)
{
irqstate_t flags;