summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog9
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs5
-rw-r--r--[-rwxr-xr-x]nuttx/arch/arm/src/stm32/stm32_can.c0
-rw-r--r--[-rwxr-xr-x]nuttx/arch/arm/src/stm32/stm32_eth.c0
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_exti.h77
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_exti_alarm.c167
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_exti_gpio.c (renamed from nuttx/arch/arm/src/stm32/stm32_exti.c)33
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_gpio.h25
-rw-r--r--[-rwxr-xr-x]nuttx/arch/arm/src/stm32/stm32_otgfsdev.c0
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_idle.c8
10 files changed, 301 insertions, 23 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index f95f9d81a..c0f7ba653 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3008,4 +3008,11 @@
* arch/arm/src/lpc43xx/lpc43_clockconfig.c and configs/lpc4330-xplorer/include/board.h:
Implement PLL1 ramp-up logic; Now the LPC43xx is running at 204MHz.
* configs/lpc4330-xplorer/*/defconfig: Re-calibrated delay loops using
- the 204MHz clock. The LPC43xx ripping rips!
+ the 204MHz clock. The LPC43xx ripping rips! This calibration was performed
+ with symbols enabled and all optimization disabled. It will need to be
+ better recalibrated again down the road.
+ * arch/arm/src/stm32/stm32_exti.c: Renamed to rch/arm/src/stm32/stm32_exti_gpio.c
+ to make a little room in the file name space.
+ * arch/arm/src/stm32/stm32_exti_alarm.c: Add initial logic to attached the
+ RTC alarm EXTI interrupt. This is work be performed mostly by Diego Sanchez.
+
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index cff2546ee..0493630b9 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -63,7 +63,7 @@ endif
CHIP_ASRCS =
CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c \
- stm32_lsi.c stm32_gpio.c stm32_exti.c stm32_flash.c stm32_irq.c \
+ stm32_lsi.c stm32_gpio.c stm32_exti_gpio.c stm32_flash.c stm32_irq.c \
stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \
stm32_spi.c stm32_sdio.c stm32_tim.c stm32_i2c.c stm32_waste.c
@@ -100,6 +100,9 @@ endif
ifeq ($(CONFIG_RTC),y)
CHIP_CSRCS += stm32_rtc.c
+ifeq ($(CONFIG_RTC_ALARM),y)
+CHIP_CSRCS += stm32_exti_alarm.c
+endif
endif
ifeq ($(CONFIG_ADC),y)
diff --git a/nuttx/arch/arm/src/stm32/stm32_can.c b/nuttx/arch/arm/src/stm32/stm32_can.c
index 7e65ecfc8..7e65ecfc8 100755..100644
--- a/nuttx/arch/arm/src/stm32/stm32_can.c
+++ b/nuttx/arch/arm/src/stm32/stm32_can.c
diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c
index 68ee78fd5..68ee78fd5 100755..100644
--- a/nuttx/arch/arm/src/stm32/stm32_eth.c
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.c
diff --git a/nuttx/arch/arm/src/stm32/stm32_exti.h b/nuttx/arch/arm/src/stm32/stm32_exti.h
index 8221ccb2d..563e7a91b 100644
--- a/nuttx/arch/arm/src/stm32/stm32_exti.h
+++ b/nuttx/arch/arm/src/stm32/stm32_exti.h
@@ -1,8 +1,8 @@
/************************************************************************************
* arch/arm/src/stm32/stm32_exti.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2009, 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
@@ -36,9 +36,82 @@
#ifndef __ARCH_ARM_SRC_STM32_STM32_EXTI_H
#define __ARCH_ARM_SRC_STM32_STM32_EXTI_H
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
#include <nuttx/config.h>
#include "chip.h"
#include "chip/stm32_exti.h"
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_gpiosetevent
+ *
+ * Description:
+ * Sets/clears GPIO based event and interrupt triggers.
+ *
+ * Parameters:
+ * - pinset: gpio pin configuration
+ * - rising/falling edge: enables
+ * - event: generate event when set
+ * - func: when non-NULL, generate interrupt
+ *
+ * Returns:
+ * The previous value of the interrupt handler function pointer. This value may,
+ * for example, be used to restore the previous handler when multiple handlers are
+ * used.
+ *
+ ************************************************************************************/
+
+EXTERN xcpt_t stm32_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
+ bool event, xcpt_t func);
+
+/****************************************************************************
+ * Name: stm32_exti_alarm
+ *
+ * Description:
+ * Sets/clears EXTI alarm interrupt.
+ *
+ * Parameters:
+ * - rising/falling edge: enables interrupt on rising/falling edget
+ * - event: generate event when set
+ * - func: when non-NULL, generate interrupt
+ *
+ * Returns:
+ * The previous value of the interrupt handler function pointer. This
+ * value may, for example, be used to restore the previous handler when
+ * multiple handlers are used.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_RTC_ALARM
+EXTERN xcpt_t stm32_exti_alarm(bool risingedge, bool fallingedge, bool event,
+ xcpt_t func);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_STM32_STM32_EXTI_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_exti_alarm.c b/nuttx/arch/arm/src/stm32/stm32_exti_alarm.c
new file mode 100644
index 000000000..fbffdc4dd
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_exti_alarm.c
@@ -0,0 +1,167 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_exti_alarm.c
+ *
+ * Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Diego Sanchez <dsanchez@nx-engineering.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <errno.h>
+
+#include <arch/irq.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_gpio.h"
+#include "stm32_exti.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* Interrupt handlers attached to the ALARM EXTI */
+
+static xcpt_t stm32_exti_callback;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+ /****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_exti_alarm_isr
+ *
+ * Description:
+ * EXTI ALRAM interrupt service routine/dispatcher
+ *
+ ****************************************************************************/
+
+static int stm32_exti_alarm_isr(int irq, void *context)
+{
+ int ret = OK;
+
+ /* Clear the pending EXTI interrupt */
+
+ putreg32(EXTI_RTC_ALARM, STM32_EXTI_PR);
+
+ /* And dispatch the interrupt to the handler */
+
+ if (stm32_exti_callback)
+ {
+ ret = stm32_exti_callback(irq, context);
+ }
+
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_exti_alarm
+ *
+ * Description:
+ * Sets/clears EXTI alarm interrupt.
+ *
+ * Parameters:
+ * - rising/falling edge: enables interrupt on rising/falling edget
+ * - event: generate event when set
+ * - func: when non-NULL, generate interrupt
+ *
+ * Returns:
+ * The previous value of the interrupt handler function pointer. This
+ * value may, for example, be used to restore the previous handler when
+ * multiple handlers are used.
+ *
+ ****************************************************************************/
+
+xcpt_t stm32_exti_alarm(bool risingedge, bool fallingedge, bool event,
+ xcpt_t func)
+{
+ xcpt_t oldhandler;
+
+ /* Get the previous GPIO IRQ handler; Save the new IRQ handler. */
+
+ oldhandler = stm32_exti_callback;
+ stm32_exti_callback = func;
+
+ /* Install external interrupt handlers (if not already attached) */
+
+ if (func)
+ {
+ irq_attach(STM32_IRQ_RTCALRM, stm32_exti_alarm_isr);
+ up_enable_irq(STM32_IRQ_RTCALRM);
+ }
+ else
+ {
+ up_disable_irq(STM32_IRQ_RTCALRM);
+ }
+
+ /* Configure rising/falling edges */
+
+ modifyreg32(STM32_EXTI_RTSR,
+ risingedge ? 0 : EXTI_RTC_ALARM,
+ risingedge ? EXTI_RTC_ALARM : 0);
+ modifyreg32(STM32_EXTI_FTSR,
+ fallingedge ? 0 : EXTI_RTC_ALARM,
+ fallingedge ? EXTI_RTC_ALARM : 0);
+
+ /* Enable Events and Interrupts */
+
+ modifyreg32(STM32_EXTI_EMR,
+ event ? 0 : EXTI_RTC_ALARM,
+ event ? EXTI_RTC_ALARM : 0);
+ modifyreg32(STM32_EXTI_IMR,
+ func ? 0 : EXTI_RTC_ALARM,
+ func ? EXTI_RTC_ALARM : 0);
+
+ /* Return the old IRQ handler */
+
+ return oldhandler;
+} \ No newline at end of file
diff --git a/nuttx/arch/arm/src/stm32/stm32_exti.c b/nuttx/arch/arm/src/stm32/stm32_exti_gpio.c
index a9fe78bb0..f897691ef 100644
--- a/nuttx/arch/arm/src/stm32/stm32_exti.c
+++ b/nuttx/arch/arm/src/stm32/stm32_exti_gpio.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/stm32/stm32_exti.c
+ * arch/arm/src/stm32/stm32_exti_gpio.c
*
* Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Copyright (C) 2011 Uros Platise. All rights reserved.
@@ -58,6 +58,7 @@
/****************************************************************************
* Private Data
****************************************************************************/
+
/* Interrupt handlers attached to each EXTI */
static xcpt_t stm32_exti_callbacks[16];
@@ -88,6 +89,7 @@ static int stm32_exti0_isr(int irq, void *context)
{
ret = stm32_exti_callbacks[0](irq, context);
}
+
return ret;
}
@@ -105,6 +107,7 @@ static int stm32_exti1_isr(int irq, void *context)
{
ret = stm32_exti_callbacks[1](irq, context);
}
+
return ret;
}
@@ -122,6 +125,7 @@ static int stm32_exti2_isr(int irq, void *context)
{
ret = stm32_exti_callbacks[2](irq, context);
}
+
return ret;
}
@@ -139,6 +143,7 @@ static int stm32_exti3_isr(int irq, void *context)
{
ret = stm32_exti_callbacks[3](irq, context);
}
+
return ret;
}
@@ -156,6 +161,7 @@ static int stm32_exti4_isr(int irq, void *context)
{
ret = stm32_exti_callbacks[4](irq, context);
}
+
return ret;
}
@@ -194,6 +200,7 @@ static int stm32_exti_multiisr(int irq, void *context, int first, int last)
}
}
}
+
return ret;
}
@@ -249,15 +256,19 @@ xcpt_t stm32_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
case 0:
handler = stm32_exti0_isr;
break;
+
case 1:
handler = stm32_exti1_isr;
break;
+
case 2:
handler = stm32_exti2_isr;
break;
+
case 3:
handler = stm32_exti3_isr;
break;
+
default:
handler = stm32_exti4_isr;
break;
@@ -291,7 +302,9 @@ xcpt_t stm32_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
up_disable_irq(irq);
}
- /* Configure GPIO, enable EXTI line enabled if event or interrupt is enabled */
+ /* Configure GPIO, enable EXTI line enabled if event or interrupt is
+ * enabled.
+ */
if (event || func)
{
@@ -302,13 +315,21 @@ xcpt_t stm32_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge,
/* Configure rising/falling edges */
- modifyreg32(STM32_EXTI_RTSR, risingedge ? 0 : exti, risingedge ? exti : 0);
- modifyreg32(STM32_EXTI_FTSR, fallingedge ? 0 : exti, fallingedge ? exti : 0);
+ modifyreg32(STM32_EXTI_RTSR,
+ risingedge ? 0 : exti,
+ risingedge ? exti : 0);
+ modifyreg32(STM32_EXTI_FTSR,
+ fallingedge ? 0 : exti,
+ fallingedge ? exti : 0);
/* Enable Events and Interrupts */
- modifyreg32(STM32_EXTI_EMR, event ? 0 : exti, event ? exti : 0);
- modifyreg32(STM32_EXTI_IMR, func ? 0 : exti, func ? exti : 0);
+ modifyreg32(STM32_EXTI_EMR,
+ event ? 0 : exti,
+ event ? exti : 0);
+ modifyreg32(STM32_EXTI_IMR,
+ func ? 0 : exti,
+ func ? exti : 0);
/* Return the old IRQ handler */
diff --git a/nuttx/arch/arm/src/stm32/stm32_gpio.h b/nuttx/arch/arm/src/stm32/stm32_gpio.h
index 07559b17a..34623c525 100644
--- a/nuttx/arch/arm/src/stm32/stm32_gpio.h
+++ b/nuttx/arch/arm/src/stm32/stm32_gpio.h
@@ -67,16 +67,6 @@
* Pre-Processor Declarations
************************************************************************************/
-#ifndef __ASSEMBLY__
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
/* Bit-encoded input to stm32_configgpio() */
#if defined(CONFIG_STM32_STM32F10XX)
@@ -390,9 +380,19 @@ extern "C" {
* Public Data
************************************************************************************/
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
/* Base addresses for each GPIO block */
-extern const uint32_t g_gpiobase[STM32_NGPIO_PORTS];
+EXTERN const uint32_t g_gpiobase[STM32_NGPIO_PORTS];
/************************************************************************************
* Public Function Prototypes
@@ -499,7 +499,8 @@ EXTERN int stm32_dumpgpio(uint32_t pinset, const char *msg);
* Based on configuration within the .config file, it does:
* - Remaps positions of alternative functions.
*
- * Typically called from stm32_start().
+ * Typically called from stm32_start().
+ *
************************************************************************************/
EXTERN void stm32_gpioinit(void);
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index 39c40d80a..39c40d80a 100755..100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
diff --git a/nuttx/configs/stm3210e-eval/src/up_idle.c b/nuttx/configs/stm3210e-eval/src/up_idle.c
index bc5be2bdc..2b92f9c5e 100644
--- a/nuttx/configs/stm3210e-eval/src/up_idle.c
+++ b/nuttx/configs/stm3210e-eval/src/up_idle.c
@@ -51,9 +51,11 @@
#include <nuttx/rtc.h>
#include <arch/irq.h>
+#include "up_internal.h"
#include "stm32_pm.h"
#include "stm32_rcc.h"
-#include "up_internal.h"
+#include "stm32_exti.h"
+
#include "stm3210e-internal.h"
/****************************************************************************
@@ -156,6 +158,10 @@ static void up_idlepm(void)
case PM_STANDBY:
{
#ifdef CONFIG_RTC_ALARM
+ /* Disable RTC Alarm interrupt */
+
+ stm32_exti_alarm(true, true, true, NULL);
+
/* Configure the RTC alarm to Auto Wake the system */
(void)up_rtc_gettime(&alarmtime);