summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-05-02 21:58:00 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-05-02 21:58:00 +0000
commit56317916d45ed401e3e6f33caff39a7d72726407 (patch)
treecf0875aa80be06e5815fc5892588400b807e8f9e /nuttx/arch
parent08b4a61636f1289a773ac4cb67f07a758f852c19 (diff)
downloadpx4-nuttx-56317916d45ed401e3e6f33caff39a7d72726407.tar.gz
px4-nuttx-56317916d45ed401e3e6f33caff39a7d72726407.tar.bz2
px4-nuttx-56317916d45ed401e3e6f33caff39a7d72726407.zip
Add XTI support
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2645 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/include/str71x/irq.h92
-rw-r--r--nuttx/arch/arm/src/str71x/Make.defs3
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_internal.h32
-rwxr-xr-xnuttx/arch/arm/src/str71x/str71x_xti.c230
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_xti.h2
5 files changed, 328 insertions, 31 deletions
diff --git a/nuttx/arch/arm/include/str71x/irq.h b/nuttx/arch/arm/include/str71x/irq.h
index 137dab715..bac58bb2a 100644
--- a/nuttx/arch/arm/include/str71x/irq.h
+++ b/nuttx/arch/arm/include/str71x/irq.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/include/str71x/irq.h
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -52,36 +52,68 @@
/* IRQ channels */
-#define STR71X_IRQ_T0TIMI (0)
-#define STR71X_IRQ_FLASH (1)
-#define STR71X_IRQ_RCCU (2)
-#define STR71X_IRQ_RTC (3)
-#define STR71X_IRQ_WDG (4)
-#define STR71X_IRQ_XTI (5)
-#define STR71X_IRQ_USBHP (6)
-#define STR71X_IRQ_I2C0ITERR (7)
-#define STR71X_IRQ_I2C1ITERR (8)
-#define STR71X_IRQ_UART0 (9)
-#define STR71X_IRQ_UART1 (10)
-#define STR71X_IRQ_UART2 (11)
-#define STR71X_IRQ_UART3 (12)
-#define STR71X_IRQ_SPI0 (13)
-#define STR71X_IRQ_SPI1 (14)
-#define STR71X_IRQ_I2C0 (15)
-#define STR71X_IRQ_I2C1 (16)
-#define STR71X_IRQ_CAN (17)
-#define STR71X_IRQ_ADC (18)
-#define STR71X_IRQ_T1TIMI (19)
-#define STR71X_IRQ_T2TIMI (20)
-#define STR71X_IRQ_T3TIMI (21)
-#define STR71X_IRQ_HDLC (25)
-#define STR71X_IRQ_USBLP (26)
-#define STR71X_IRQ_T0TOI (29)
-#define STR71X_IRQ_T0OC1 (30)
-#define STR71X_IRQ_T0OC2 (31)
+#define STR71X_IRQ_T0TIMI (0) /* IRQ 0: T0.EFTI Timer 0 global interrupt */
+#define STR71X_IRQ_FLASH (1) /* IRQ 1: FLASH FLASH global interrupt */
+#define STR71X_IRQ_RCCU (2) /* IRQ 2: PRCCU PRCCU global interrupt */
+#define STR71X_IRQ_RTC (3) /* IRQ 3: RTC Real Time Clock global interrupt */
+#define STR71X_IRQ_WDG (4) /* IRQ 4: WDG.IRQ Watchdog timer interrupt */
+#define STR71X_IRQ_XTI (5) /* IRQ 5: XTI.IRQ XTI external interrupt */
+#define STR71X_IRQ_USBHP (6) /* IRQ 6: USB.HPIRQ USB high priority event interrupt */
+#define STR71X_IRQ_I2C0ITERR (7) /* IRQ 7: I2C0.ITERR I2C 0 error interrupt */
+#define STR71X_IRQ_I2C1ITERR (8) /* IRQ 8: I2C1.ITERR I2C 1 error interrupt */
+#define STR71X_IRQ_UART0 (9) /* IRQ 9: UART0.IRQ UART 0 global interrupt */
+#define STR71X_IRQ_UART1 (10) /* IRQ 10: UART1.IRQ UART 1 global interrupt */
+#define STR71X_IRQ_UART2 (11) /* IRQ 11: UART2.IRQ UART 2 global interrupt */
+#define STR71X_IRQ_UART3 (12) /* IRQ 12: UART3.IRQ UART 3 global interrupt */
+#define STR71X_IRQ_SPI0 (13) /* IRQ 13: BSPI0.IRQ BSPI 0 global interrupt */
+#define STR71X_IRQ_SPI1 (14) /* IRQ 14: BSPI1.IRQ BSPI 1 global interrupt */
+#define STR71X_IRQ_I2C0 (15) /* IRQ 15: I2C0.IRQ I2C 0 tx/rx interrupt */
+#define STR71X_IRQ_I2C1 (16) /* IRQ 16: I2C1.IRQ I2C 1 tx/rx interrupt */
+#define STR71X_IRQ_CAN (17) /* IRQ 17: CAN.IRQ CAN module global interrupt */
+#define STR71X_IRQ_ADC (18) /* IRQ 18: ADC.IRQ ADC sample ready interrupt */
+#define STR71X_IRQ_T1TIMI (19) /* IRQ 19: T1.GI Timer 1 global interrupt */
+#define STR71X_IRQ_T2TIMI (20) /* IRQ 20: T2.GI Timer 2 global interrupt */
+#define STR71X_IRQ_T3TIMI (21) /* IRQ 21: T3.GI Timer 3 global interrupt */
+ /* IRQ 22-24: Reserved */
+#define STR71X_IRQ_HDLC (25) /* IRQ 25: HDLC.IRQ HDLC global interrupt */
+#define STR71X_IRQ_USBLP (26) /* IRQ 26: USB.LPIRQ USB low priority event interrupt */
+ /* IRQ 27-28: Reserved */
+#define STR71X_IRQ_T0TOI (29) /* IRQ 29: T0.TOI Timer 0 Overflow interrupt */
+#define STR71X_IRQ_T0OC1 (30) /* IRQ 30: T0.OCMPA Timer 0 Output Compare A interrupt */
+#define STR71X_IRQ_T0OC2 (31) /* IRQ 31: T0.OCMPB Timer 0 Output Compare B interrupt */
+
+#define STR71X_NBASEIRQS (32)
+
+#ifdef CONFIG_STR71X_XTI
+# define STR71X_IRQ_FIRSTXTI (32)
+# define STR71X_IRQ_SW (32) /* Line 0: SW interrupt - no HW connection */
+# define STR71X_IRQ_USBWKUP (33) /* Line 1: USB wake-up event: generated while exiting
+ * from suspend mode */
+# define STR71X_IRQ_PORT2p8 (34) /* Line 2: Port 2.8 - External Interrupt */
+# define STR71X_IRQ_PORT2p9 (35) /* Line 3: Port 2.9 - External Interrupt */
+# define STR71X_IRQ_PORT2p10 (36) /* Line 4: Port 2.10 - External Interrupt */
+# define STR71X_IRQ_PORT2p11 (37) /* Line 5: Port 2.11 - External Interrupt */
+# define STR71X_IRQ_PORT1p11 (38) /* Line 6: Port 1.11 - CAN module receive pin (CANRX). */
+# define STR71X_IRQ_PORT1p13 (39) /* Line 7: Port 1.13 - HDLC clock (HCLK) or I2C.0 Clock
+ * (I0.SCL) */
+# define STR71X_IRQ_PORT1p14 (40) /* Line 8: Port 1.14 - HDLC receive pin (HRXD) or I2C.0
+ * Data (SDA) */
+# define STR71X_IRQ_PORT0p1 (41) /* Line 9: Port 0.1 - BSPI0 Slave Input data (S0.MOSI)
+ * or UART3 Receive Data Input (U3.Rx) */
+# define STR71X_IRQ_PORT0p2 (42) /* Line 10: Port 0.2 - BSPI0 Slave Input serial clock
+ * (S0.SCLK) or I2C.1 Clock (I1.SCL) */
+# define STR71X_IRQ_PORT0p6 (43) /* Line 11: Port 0.6 - BSPI1 Slave Input serial clock
+ * (S1.SCLK) */
+# define STR71X_IRQ_PORT0p8 (44) /* Line 12: Port 0.8 - UART0 Receive Data Input (U0.Rx) */
+# define STR71X_IRQ_PORT0p10 (45) /* Line 13: Port 0.10 - UART1 Receive Data Input (U1.Rx) */
+# define STR71X_IRQ_PORT0p13 (46) /* Line 14: Port 0.13 - UART2 Receive Data Input (U2.Rx) */
+# define STR71X_IRQ_PORT0p15 (47) /* Line 15: Port 0.15 - WAKEUP pin or RTC ALARM */
+# define NR_IRQS (48)
+#else
+# define NR_IRQS (32)
+#endif
#define STR71X_IRQ_SYSTIMER STR71X_IRQ_T0TIMI
-#define NR_IRQS 32
/* FIQ channels */
@@ -113,7 +145,7 @@ extern "C" {
#ifdef __cplusplus
}
#endif
-#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_INCLUDE_STR71X_IRQ_H */
diff --git a/nuttx/arch/arm/src/str71x/Make.defs b/nuttx/arch/arm/src/str71x/Make.defs
index c6e0e23c4..4ca4edff4 100644
--- a/nuttx/arch/arm/src/str71x/Make.defs
+++ b/nuttx/arch/arm/src/str71x/Make.defs
@@ -54,4 +54,7 @@ CHIP_CSRCS = str71x_prccu.c str71x_lowputc.c str71x_decodeirq.c str71x_irq.c \
ifeq ($(CONFIG_USBDEV),y)
CHIP_CSRCS += str71x_usbdev.c
endif
+ifeq ($(CONFIG_STR71X_XTI),y)
+CHIP_CSRCS += str71x_xti.c
+endif
diff --git a/nuttx/arch/arm/src/str71x/str71x_internal.h b/nuttx/arch/arm/src/str71x/str71x_internal.h
index 468c48600..6c8913376 100644
--- a/nuttx/arch/arm/src/str71x/str71x_internal.h
+++ b/nuttx/arch/arm/src/str71x/str71x_internal.h
@@ -42,6 +42,8 @@
#include <nuttx/config.h>
+#include <stdbool.h>
+
#include <arch/board/board.h>
/************************************************************************************
@@ -92,4 +94,34 @@
* Public Functions
************************************************************************************/
+/********************************************************************************
+ * Name: str7x_xtiinitialize
+ *
+ * Description:
+ * Configure XTI for operation. Note that the lines are not used as wake-up
+ * sources in this implementation. Some extensions would be required for that
+ * capability.
+ *
+ ********************************************************************************/
+
+#ifdef CONFIG_STR71X_XTI
+extern int str7x_xtiinitialize(void);
+#else
+# define str7x_xtiinitialize()
+#endif /* CONFIG_STR71X_XTI */
+
+/********************************************************************************
+ * Name: str7x_xticonfig
+ *
+ * Description:
+ * Configure an external line to provide interrupts.
+ *
+ ********************************************************************************/
+
+#ifdef CONFIG_STR71X_XTI
+extern int str7x_xticonfig(int irq, bool rising);
+#else
+# define str7x_xticonfig(irq,rising)
+#endif /* CONFIG_STR71X_XTI */
+
#endif /* __ARCH_ARM_SRC_STR71X_STR71X_INTERNAL_H */
diff --git a/nuttx/arch/arm/src/str71x/str71x_xti.c b/nuttx/arch/arm/src/str71x/str71x_xti.c
new file mode 100755
index 000000000..e95e4349b
--- /dev/null
+++ b/nuttx/arch/arm/src/str71x/str71x_xti.c
@@ -0,0 +1,230 @@
+/********************************************************************************
+ * arch/arm/src/str71x/str71x_xti.c
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "os_internal.h"
+#include "up_internal.h"
+
+#ifdef CONFIG_STR71X_XTI
+
+/********************************************************************************
+ * Pre-procesor Definitions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Types
+ ********************************************************************************/
+
+struct xtiregs_s
+{
+ uint32_t mr; /* Mask register */
+ uint32_t tr; /* Trigger polarity register */
+};
+
+/********************************************************************************
+ * Public Data
+ ********************************************************************************/
+
+static const struct xtiregs_s g_xtiregs[2] =
+{
+ { STR71X_XTI_MRL, STR71X_XTI_TRL },
+ { STR71X_XTI_MRH, STR71X_XTI_TRH }
+};
+
+/********************************************************************************
+ * Private Data
+ ********************************************************************************/
+
+/********************************************************************************
+ * Private Functions
+ ********************************************************************************/
+
+static int str7x_xtiinterrupt(int irq, FAR void *context)
+{
+ uint16_t enabled = (uint16_t)getreg8(STR71X_XTI_MRH) << 8 |
+ (uint16_t)getreg8(STR71X_XTI_MRL);
+ uint16_t pending = (uint16_t)getreg8(STR71X_XTI_PRH) << 8 |
+ (uint16_t)getreg8(STR71X_XTI_PRL);
+ uint16_t mask;
+
+ /* Clear the interrupts now. This seems unsafe? Couldn't this cause lost
+ * interupts?
+ */
+
+ mask = ~pending;
+ putreg8(mask >> 8, STR71X_XTI_PRH);
+ putreg8(mask & 0xff, STR71X_XTI_PRH);
+
+ /* Then dispatch the interrupts */
+
+ pending &= enabled;
+
+ for (irq = STR71X_IRQ_FIRSTXTI, mask = 0x0001;
+ irq < NR_IRQS && pending != 0;
+ irq++, mask <<= 1)
+ {
+ /* Is this interrupt pending? */
+
+ if ((pending & mask) != 0)
+ {
+ /* Deliver the IRQ */
+
+ irq_dispatch(irq, context);
+ pending &= ~mask;
+ }
+ }
+ return OK;
+}
+
+/********************************************************************************
+ * Public Functions
+ ********************************************************************************/
+
+/********************************************************************************
+ * Name: str7x_xtiinitialize
+ *
+ * Description:
+ * Configure XTI for operation. Note that the lines are not used as wake-up
+ * sources in this implementation. Some extensions would be required for that
+ * capability.
+ *
+ ********************************************************************************/
+
+int str7x_xtiinitialize(void)
+{
+ int ret;
+
+ /* Mask all interrupts by setting XTI MRH/L to zero */
+
+ putreg8(0, STR71X_XTI_MRH);
+ putreg8(0, STR71X_XTI_MRL);
+
+ /* Clear any pending interrupts by setting XTI PRH/L to zero */
+
+ putreg8(0, STR71X_XTI_PRH);
+ putreg8(0, STR71X_XTI_PRL);
+
+ /* Attach the XTI interrupt */
+
+ ret = irq_attach(STR71X_IRQ_XTI, str7x_xtiinterrupt);
+ if (ret == OK)
+ {
+ /* Enable the XTI interrupt at the XTI */
+
+ putreg8(STR71X_XTICTRL_ID1S, STR71X_XTI_CTRL);
+
+ /* And enable the XTI interrupt at the interrupt controller */
+
+ up_enable_irq(STR71X_IRQ_XTI);
+ }
+ return ret;
+}
+
+/********************************************************************************
+ * Name: str7x_xticonfig
+ *
+ * Description:
+ * Configure an external line to provide interrupts.
+ *
+ ********************************************************************************/
+
+int str7x_xticonfig(int irq, bool rising)
+{
+ uint8_t regval;
+ int bit;
+ int ndx;
+ int ret = -EINVAL;
+
+ /* Configure one of the 16 lines as an interrupt source */
+
+ if (irq > STR71X_IRQ_FIRSTXTI && irq <= NR_IRQS)
+ {
+ /* Decide if we use the lower or upper regiser */
+
+ bit = irq - STR71X_IRQ_FIRSTXTI;
+ ndx = 0;
+ if (bit > 7)
+ {
+ /* Select the high register */
+
+ bit -= 8;
+ ndx = 1;
+ }
+
+ /* Set the rising or trailing edge */
+
+ regval = getreg8(g_xtiregs[ndx].tr);
+ if (rising)
+ {
+ regval |= (1 << bit);
+ }
+ else
+ {
+ regval &= ~(1 << bit);
+ }
+ putreg8(regval, g_xtiregs[ndx].tr);
+
+ /* Enable the interrupt be setting the corresponding mask bit
+ * the XTI_MRL/H register.
+ */
+
+ regval = getreg8(g_xtiregs[ndx].mr);
+ regval |= (1 << bit);
+ putreg8(regval, g_xtiregs[ndx].mr);
+
+ /* Return success */
+
+ ret = OK;
+ }
+ return ret;
+}
+
+#endif /* CONFIG_STR71X_XTI */
diff --git a/nuttx/arch/arm/src/str71x/str71x_xti.h b/nuttx/arch/arm/src/str71x/str71x_xti.h
index bbe3c46e0..d9458c196 100644
--- a/nuttx/arch/arm/src/str71x/str71x_xti.h
+++ b/nuttx/arch/arm/src/str71x/str71x_xti.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/str71x/str71x_xti.h
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without