summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-06-06 16:01:38 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-06-06 16:01:38 +0000
commitf99c82323ed00c8e417ca0c971ffa9a7ba0d9a1d (patch)
treeeb81a980d8031b001df4a9d9a52d6f3de914043d /nuttx/arch
parent2a86d0f5169f0122a75dd22ee932bae2e6adfecb (diff)
downloadpx4-nuttx-f99c82323ed00c8e417ca0c971ffa9a7ba0d9a1d.tar.gz
px4-nuttx-f99c82323ed00c8e417ca0c971ffa9a7ba0d9a1d.tar.bz2
px4-nuttx-f99c82323ed00c8e417ca0c971ffa9a7ba0d9a1d.zip
More UART GPIO pin/interrupt fixes
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1858 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_gpio.h2
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_irq.c4
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_lowputc.c6
-rw-r--r--nuttx/arch/arm/src/str71x/str71x_serial.c8
4 files changed, 12 insertions, 8 deletions
diff --git a/nuttx/arch/arm/src/str71x/str71x_gpio.h b/nuttx/arch/arm/src/str71x/str71x_gpio.h
index 2eb92939a..d8e307ec3 100644
--- a/nuttx/arch/arm/src/str71x/str71x_gpio.h
+++ b/nuttx/arch/arm/src/str71x/str71x_gpio.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/str71x/str71x_gpio.h
*
- * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/str71x/str71x_irq.c b/nuttx/arch/arm/src/str71x/str71x_irq.c
index 6be5e945b..d9804e174 100644
--- a/nuttx/arch/arm/src/str71x/str71x_irq.c
+++ b/nuttx/arch/arm/src/str71x/str71x_irq.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <errno.h>
#include <nuttx/irq.h>
+#include <nuttx/arch.h>
#include "arm.h"
#include "up_arch.h"
@@ -92,8 +93,11 @@ void up_irqinitialize(void)
* (Needs more investigation).
*/
+ up_mdelay(50); /* Wait a bit */
+#if 0
putreg32(0, STR71X_EIC_IER); /* Make sure that all interrupts are disabled */
putreg32(0xffffffff, STR71X_EIC_IPR); /* And that no interrupts are pending */
+#endif
/* Enable global ARM interrupts */
diff --git a/nuttx/arch/arm/src/str71x/str71x_lowputc.c b/nuttx/arch/arm/src/str71x/str71x_lowputc.c
index b12936653..ae20cbb26 100644
--- a/nuttx/arch/arm/src/str71x/str71x_lowputc.c
+++ b/nuttx/arch/arm/src/str71x/str71x_lowputc.c
@@ -300,17 +300,17 @@ void up_lowsetup(void)
#if HAVE_UART
reg16 = getreg16(STR71X_GPIO0_PC0);
- reg16 &= STR71X_UART_GPIO0_MASK;
+ reg16 &= ~STR71X_UART_GPIO0_MASK;
reg16 |= STR71X_UART_GPIO0_PC0BITS;
putreg16(reg16, STR71X_GPIO0_PC0);
reg16 = getreg16(STR71X_GPIO0_PC1);
- reg16 &= STR71X_UART_GPIO0_MASK;
+ reg16 &= ~STR71X_UART_GPIO0_MASK;
reg16 |= STR71X_UART_GPIO0_PC1BITS;
putreg16(reg16, STR71X_GPIO0_PC1);
reg16 = getreg16(STR71X_GPIO0_PC2);
- reg16 &= STR71X_UART_GPIO0_MASK;
+ reg16 &= ~STR71X_UART_GPIO0_MASK;
reg16 |= STR71X_UART_GPIO0_PC2BITS;
putreg16(reg16, STR71X_GPIO0_PC2);
#endif
diff --git a/nuttx/arch/arm/src/str71x/str71x_serial.c b/nuttx/arch/arm/src/str71x/str71x_serial.c
index 1f82f7f4f..340c166cb 100644
--- a/nuttx/arch/arm/src/str71x/str71x_serial.c
+++ b/nuttx/arch/arm/src/str71x/str71x_serial.c
@@ -775,17 +775,17 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
if (enable)
{
- /* Receive an interrupt when the Rx FIFO is half full (or an IDLE
- * timeout occurs.
+ /* Receive an interrupt when the Rx FIFO is half full (or if a timeout
+ * occurs while the Rx FIFO is not empty).
*/
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
- priv->ier |= (STR71X_UARTIER_RHF|STR71X_UARTIER_TIMEOUTIDLE);
+ priv->ier |= (STR71X_UARTIER_RHF|STR71X_UARTIER_TIMEOUTNE);
#endif
}
else
{
- priv->ier &= ~(STR71X_UARTIER_RHF|STR71X_UARTIER_TIMEOUTIDLE);
+ priv->ier &= ~(STR71X_UARTIER_RHF|STR71X_UARTIER_TIMEOUTNE);
}
up_serialout(priv, STR71X_UART_IER_OFFSET, priv->ier);
}