summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-20 19:47:40 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-20 19:47:40 +0000
commit06fa41316a30d98aeda6a6016b5c139dbeaa34d6 (patch)
treec7548477e32b4cbe2c1017a0f4496de5f5099230
parent78538c8d3257913599ea721b55b6ce56fd8988f3 (diff)
downloadpx4-nuttx-06fa41316a30d98aeda6a6016b5c139dbeaa34d6.tar.gz
px4-nuttx-06fa41316a30d98aeda6a6016b5c139dbeaa34d6.tar.bz2
px4-nuttx-06fa41316a30d98aeda6a6016b5c139dbeaa34d6.zip
Finish m9s12x interrupt logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3307 42af7a65-404d-4744-a932-0658087f49c3
-rwxr-xr-xnuttx/arch/hc/include/hcs12/irq.h74
-rwxr-xr-xnuttx/arch/hc/include/hcs12/types.h2
-rw-r--r--nuttx/arch/hc/src/common/up_doirq.c8
-rw-r--r--nuttx/arch/hc/src/m9s12/m9s12_assert.c17
-rw-r--r--nuttx/arch/hc/src/m9s12/m9s12_initialstate.c8
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_irq.c43
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_serial.c24
-rwxr-xr-xnuttx/arch/hc/src/m9s12/m9s12_timerisr.c4
-rwxr-xr-xnuttx/configs/demo9s12ne64/ostest/defconfig4
9 files changed, 88 insertions, 96 deletions
diff --git a/nuttx/arch/hc/include/hcs12/irq.h b/nuttx/arch/hc/include/hcs12/irq.h
index 22e9dd6b4..cb3eb8ecb 100755
--- a/nuttx/arch/hc/include/hcs12/irq.h
+++ b/nuttx/arch/hc/include/hcs12/irq.h
@@ -50,6 +50,17 @@
/************************************************************************************
* Definitions
************************************************************************************/
+/* CCR bit definitions */
+
+#define HCS12_CCR_C (1 << 0) /* Bit 0: Carry/Borrow status bit */
+#define HCS12_CCR_V (1 << 1) /* Bit 1: Two’s complement overflow status bit */
+#define HCS12_CCR_Z (1 << 2) /* Bit 2: Zero status bit */
+#define HCS12_CCR_N (1 << 3) /* Bit 3: Negative status bit */
+#define HCS12_CCR_I (1 << 4) /* Bit 4: Maskable interrupt control bit */
+#define HCS12_CCR_H (1 << 5) /* Bit 5: Half-carry status bit */
+#define HCS12_CCR_X (1 << 6) /* Bit 6: Non-maskable interrupt control bit */
+#define HCS12_CCR_S (1 << 7) /* Bit 7: STOP instruction control bit */
+
/************************************************************************************
* Register state save strucure
* Low Address <-- SP after state save
@@ -167,26 +178,73 @@ struct xcptcontext
* Inline functions
****************************************************************************/
+/* Enable/Disable interrupts */
+
+#define ienable() __asm("cli");
+#define idisable() __asm("orcc #0x10")
+#define xenable() __asm("andcc #0xbf")
+#define xdisable() __asm("orcc #0x40")
+
+/* Get the current value of the stack pointer */
+
+static inline uint16_t up_getsp(void)
+{
+ uint16_t ret;
+ __asm__
+ (
+ "\tsts %0\n"
+ : "=m"(ret) :
+ );
+ return ret;
+}
+
+/* Get the current value of the CCR */
+
+static inline irqstate_t up_getccr(void)
+{
+ irqstate_t ccr;
+ __asm__
+ (
+ "\ttpa\n"
+ "\tstaa %0\n"
+ : "=m"(ccr) :
+ );
+ return ccr;
+}
+
/* Save the current interrupt enable state & disable IRQs */
static inline irqstate_t irqsave(void)
{
- /* To be provided */
+ irqstate_t ccr;
+ __asm__
+ (
+ "\ttpa\n"
+ "\tstaa %0\n"
+ "\torcc #0x50\n"
+ : "=m"(ccr) :
+ );
+ return ccr;
}
-/* Restore saved IRQ & FIQ state */
+/* Restore saved interrupt state */
static inline void irqrestore(irqstate_t flags)
{
- /* To be provided */
-}
+ /* Should interrupts be enabled? */
-static inline void system_call(swint_t func, int parm1,
- int parm2, int parm3)
-{
- /* To be provided */
+ if ((flags & HCS12_CCR_I) == 0)
+ {
+ /* Yes.. unmask I- and Z-interrupts */
+
+ __asm("andcc #0xaf");
+ }
}
+/* System call */
+
+#define system_call(f,p1,p2,p3) __asm("swi")
+
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx/arch/hc/include/hcs12/types.h b/nuttx/arch/hc/include/hcs12/types.h
index 33008793a..71b311fb7 100755
--- a/nuttx/arch/hc/include/hcs12/types.h
+++ b/nuttx/arch/hc/include/hcs12/types.h
@@ -93,7 +93,7 @@ typedef unsigned short _uintptr_t;
/* This is the size of the interrupt state save returned by irqsave()*/
-typedef unsigned int irqstate_t;
+typedef unsigned char irqstate_t;
#endif /* __ASSEMBLY__ */
diff --git a/nuttx/arch/hc/src/common/up_doirq.c b/nuttx/arch/hc/src/common/up_doirq.c
index d3de013fa..05dbaa2cf 100644
--- a/nuttx/arch/hc/src/common/up_doirq.c
+++ b/nuttx/arch/hc/src/common/up_doirq.c
@@ -89,10 +89,6 @@ uint8_t *up_doirq(int irq, uint8_t *regs)
DEBUGASSERT(current_regs == NULL);
current_regs = regs;
- /* Mask and acknowledge the interrupt */
-
- up_maskack_irq(irq);
-
/* Deliver the IRQ */
irq_dispatch(irq, regs);
@@ -108,10 +104,6 @@ uint8_t *up_doirq(int irq, uint8_t *regs)
/* Indicate that we are no long in an interrupt handler */
current_regs = NULL;
-
- /* Unmask the last interrupt (global interrupts are still disabled) */
-
- up_enable_irq(irq);
#endif
up_ledoff(LED_INIRQ);
return regs;
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_assert.c b/nuttx/arch/hc/src/m9s12/m9s12_assert.c
index 7b167d183..97d18b64f 100644
--- a/nuttx/arch/hc/src/m9s12/m9s12_assert.c
+++ b/nuttx/arch/hc/src/m9s12/m9s12_assert.c
@@ -87,23 +87,6 @@
****************************************************************************/
/****************************************************************************
- * Name: up_getsp
- ****************************************************************************/
-
-/* I don't know if the builtin to get SP is enabled */
-
-static inline uint16_t up_getsp(void)
-{
- uint16_t spval;
- __asm__
- (
- "\tsts spval\n"
- : "=A"(spval) :
- );
- return spval;
-}
-
-/****************************************************************************
* Name: up_stackdump
****************************************************************************/
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_initialstate.c b/nuttx/arch/hc/src/m9s12/m9s12_initialstate.c
index 7efe77942..c537546b1 100644
--- a/nuttx/arch/hc/src/m9s12/m9s12_initialstate.c
+++ b/nuttx/arch/hc/src/m9s12/m9s12_initialstate.c
@@ -113,9 +113,13 @@ void up_initial_state(_TCB *tcb)
*/
# ifdef CONFIG_SUPPRESS_INTERRUPTS
- xcp->regs[REG_CCR] = 0xd0; /* Disable STOP, Mask I- and Z- interrupts */
+ /* Disable STOP, Mask I- and Z- interrupts */
+
+ xcp->regs[REG_CCR] = HCS12_CCR_S|HCS12_CCR_X|HCS12_CCR_I;
# else
- xcp->regs[REG_CCR] = 0x80; /* Disable STOP, Enable I- and Z-interrupts */
+ /* Disable STOP, Enable I- and Z-interrupts */
+
+ xcp->regs[REG_CCR] = HCS12_CCR_S;
# endif
}
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_irq.c b/nuttx/arch/hc/src/m9s12/m9s12_irq.c
index 20a86e1ef..1fb59d551 100755
--- a/nuttx/arch/hc/src/m9s12/m9s12_irq.c
+++ b/nuttx/arch/hc/src/m9s12/m9s12_irq.c
@@ -80,50 +80,7 @@ uint8_t *current_regs;
void up_irqinitialize(void)
{
- /* Disable all interrupts */
-#warning "Missing Logic"
-
/* currents_regs is non-NULL only while processing an interrupt */
current_regs = NULL;
-
-}
-
-/****************************************************************************
- * Name: up_disable_irq
- *
- * Description:
- * Disable the IRQ specified by 'irq'
- *
- ****************************************************************************/
-
-void up_disable_irq(int irq)
-{
-#warning "Missing Logic"
-}
-
-/****************************************************************************
- * Name: up_enable_irq
- *
- * Description:
- * Enable the IRQ specified by 'irq'
- *
- ****************************************************************************/
-
-void up_enable_irq(int irq)
-{
-#warning "Missing Logic"
-}
-
-/****************************************************************************
- * Name: up_maskack_irq
- *
- * Description:
- * Mask the IRQ and acknowledge it
- *
- ****************************************************************************/
-
-void up_maskack_irq(int irq)
-{
-#warning "Missing Logic"
}
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_serial.c b/nuttx/arch/hc/src/m9s12/m9s12_serial.c
index 6d60ee9bc..7b5ba365e 100755
--- a/nuttx/arch/hc/src/m9s12/m9s12_serial.c
+++ b/nuttx/arch/hc/src/m9s12/m9s12_serial.c
@@ -331,7 +331,9 @@ static int up_setup(struct uart_dev_s *dev)
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
#ifndef CONFIG_SUPPRESS_SCI_CONFIG
uint8_t cr1;
+#endif
+#ifndef CONFIG_SUPPRESS_SCI_CONFIG
/* Calculate the BAUD divisor */
tmp = SCIBR_VALUE(priv->baud);
@@ -371,17 +373,12 @@ static int up_setup(struct uart_dev_s *dev)
up_serialout(priv, HCS12_SCI_CR1_OFFSET, cr1);
#endif
- /* Enable Rx interrupts from the SCI. We don't want Tx interrupts until we
- * have something to send. We will check for serial errors as part of Rx
- * interrupt processing. Interrupts won't be fully enabled until the
- * interrupt vector is attached.
+ /* Enable Rx and Tx, keeping all interrupts disabled. We don't want
+ * interrupts until the interrupt vector is attached.
*/
- priv->im = SCI_CR2_RIE;
-
- /* Enable Rx and Tx */
-
- up_serialout(priv, HCS12_SCI_CR2_OFFSET, (SCI_CR2_RIE|SCI_CR2_TE|SCI_CR2_RE));
+ priv->im = 0;
+ up_serialout(priv, HCS12_SCI_CR2_OFFSET, (SCI_CR2_TE|SCI_CR2_RE));
return OK;
}
@@ -424,11 +421,12 @@ static int up_attach(struct uart_dev_s *dev)
ret = irq_attach(priv->irq, up_interrupt);
if (ret == OK)
{
- /* Enable the interrupt (RX and TX interrupts are still disabled
- * in the SCI
+ /* Enable the Rx interrupt (the TX interrupt is still disabled
+ * until we have something to send).
*/
- up_enable_irq(priv->irq);
+ priv->im = SCI_CR2_RIE;
+ up_setsciint(priv);
}
return ret;
}
@@ -446,7 +444,7 @@ static int up_attach(struct uart_dev_s *dev)
static void up_detach(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- up_disable_irq(priv->irq);
+ up_disablesciint(priv, NULL);
irq_detach(priv->irq);
}
diff --git a/nuttx/arch/hc/src/m9s12/m9s12_timerisr.c b/nuttx/arch/hc/src/m9s12/m9s12_timerisr.c
index 3839badf2..22e76d7ee 100755
--- a/nuttx/arch/hc/src/m9s12/m9s12_timerisr.c
+++ b/nuttx/arch/hc/src/m9s12/m9s12_timerisr.c
@@ -182,8 +182,4 @@ void up_timerinit(void)
regval = getreg8(HCS12_CRG_CRGINT);
regval |= CRG_CRGINT_RTIE;
putreg8(regval, HCS12_CRG_CRGINT);
-
- /* And enable the timer interrupt */
-
- up_enable_irq(HCS12_IRQ_VRTI);
}
diff --git a/nuttx/configs/demo9s12ne64/ostest/defconfig b/nuttx/configs/demo9s12ne64/ostest/defconfig
index fc52adf26..9c2afdf33 100755
--- a/nuttx/configs/demo9s12ne64/ostest/defconfig
+++ b/nuttx/configs/demo9s12ne64/ostest/defconfig
@@ -52,6 +52,9 @@
# CONFIG_DRAM_SIZE - Describes the installed RAM.
# CONFIG_DRAM_START - The start address of RAM (physical)
# CONFIG_DRAM_END - Last address+1 of installed RAM
+# CONFIG_ARCH_NOINTC - define if the architecture does not
+# support an interrupt controller or otherwise cannot support
+# APIs like up_enable_irq() and up_disable_irq().
# CONFIG_ARCH_IRQPRIO - The ST32F103Z supports interrupt prioritization
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
@@ -80,6 +83,7 @@ CONFIG_BOARD_LOOPSPERMSEC=5483
CONFIG_DRAM_SIZE=0x00010000
CONFIG_DRAM_START=0x20000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
+CONFIG_ARCH_NOINTC=y
CONFIG_ARCH_IRQPRIO=n
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y