summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/c5471/src/up_doirq.c1
-rw-r--r--nuttx/arch/dm320/defconfig5
-rw-r--r--nuttx/arch/dm320/ld.script2
-rw-r--r--nuttx/arch/dm320/src/up_allocateheap.c3
-rw-r--r--nuttx/arch/dm320/src/up_doirq.c1
-rw-r--r--nuttx/arch/dm320/src/up_internal.h2
-rw-r--r--nuttx/arch/dm320/src/up_serial.c7
-rw-r--r--nuttx/drivers/serial.c44
8 files changed, 9 insertions, 56 deletions
diff --git a/nuttx/arch/c5471/src/up_doirq.c b/nuttx/arch/c5471/src/up_doirq.c
index ab1b40d65..73d6f8a76 100644
--- a/nuttx/arch/c5471/src/up_doirq.c
+++ b/nuttx/arch/c5471/src/up_doirq.c
@@ -97,7 +97,6 @@ void up_doirq(int irq, uint32* regs)
* disabled.
*/
- current_regs = NULL;
up_enable_irq(irq);
}
up_ledoff(LED_INIRQ);
diff --git a/nuttx/arch/dm320/defconfig b/nuttx/arch/dm320/defconfig
index 4bf241ebe..aaea0c3e5 100644
--- a/nuttx/arch/dm320/defconfig
+++ b/nuttx/arch/dm320/defconfig
@@ -38,13 +38,12 @@
# CONFIG_ARCH - identifies the arch subdirectory
# CONFIG_ARCH_name - for use in C code
# CONFIG_ROM_VECTORS - unique to dm320
-# CONFIG_DRAM_START/SIZE - Describes the installed DRAM.
+# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
#
CONFIG_ARCH=dm320
CONFIG_ARCH_DM320=y
CONFIG_ROM_VECTORS=n
-CONFIG_DRAM_START=0x01000000
CONFIG_DRAM_SIZE=0x01000000
CONFIG_DRAM_NUTTXENTRY=0x01008000
CONFIG_ARCH_STACKDUMP=y
@@ -117,7 +116,7 @@ CONFIG_START_YEAR=2007
CONFIG_START_MONTH=2
CONFIG_START_DAY=13
CONFIG_JULIAN_TIME=n
-CONFIG_DEV_CONSOLE=n
+CONFIG_DEV_CONSOLE=y
#
# The following can be used to disable categories of
diff --git a/nuttx/arch/dm320/ld.script b/nuttx/arch/dm320/ld.script
index 6ee7a5db3..b048f088a 100644
--- a/nuttx/arch/dm320/ld.script
+++ b/nuttx/arch/dm320/ld.script
@@ -39,7 +39,7 @@ SECTIONS
{
/* The OS entry point is here */
- . = 0x01008000;
+ . = 0x00008000;
.text : {
_stext = ABSOLUTE(.);
*(.text)
diff --git a/nuttx/arch/dm320/src/up_allocateheap.c b/nuttx/arch/dm320/src/up_allocateheap.c
index 871637ce4..697818e8d 100644
--- a/nuttx/arch/dm320/src/up_allocateheap.c
+++ b/nuttx/arch/dm320/src/up_allocateheap.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <debug.h>
#include <nuttx/arch.h>
+#include "dm320.h"
#include "up_internal.h"
/************************************************************
@@ -73,5 +74,5 @@
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
{
*heap_start = (FAR void*)g_heapbase;
- *heap_size = (CONFIG_DRAM_START + CONFIG_DRAM_SIZE) - g_heapbase;
+ *heap_size = (DM320_SDRAM_VADDR + CONFIG_DRAM_SIZE) - g_heapbase;
}
diff --git a/nuttx/arch/dm320/src/up_doirq.c b/nuttx/arch/dm320/src/up_doirq.c
index c2981dd4e..7f53f5eae 100644
--- a/nuttx/arch/dm320/src/up_doirq.c
+++ b/nuttx/arch/dm320/src/up_doirq.c
@@ -96,7 +96,6 @@ void up_doirq(int irq, uint32* regs)
* disabled.
*/
- current_regs = NULL;
up_enable_irq(irq);
}
#endif
diff --git a/nuttx/arch/dm320/src/up_internal.h b/nuttx/arch/dm320/src/up_internal.h
index 7420d3053..58f341793 100644
--- a/nuttx/arch/dm320/src/up_internal.h
+++ b/nuttx/arch/dm320/src/up_internal.h
@@ -53,7 +53,7 @@
#undef CONFIG_SUPPRESS_TIMER_INTS /* No timer */
#undef CONFIG_SUPPRESS_SERIAL_INTS /* Console will poll */
#undef CONFIG_SUPPRESS_UART_CONFIG /* Do not reconfig UART */
-#undef CONFIG_DUMP_ON_EXIT /* Dump task state on exit */
+#define CONFIG_DUMP_ON_EXIT 1 /* Dump task state on exit */
/************************************************************
* Public Types
diff --git a/nuttx/arch/dm320/src/up_serial.c b/nuttx/arch/dm320/src/up_serial.c
index fadc90958..c34e2bb2f 100644
--- a/nuttx/arch/dm320/src/up_serial.c
+++ b/nuttx/arch/dm320/src/up_serial.c
@@ -281,7 +281,7 @@ static inline void up_enablebreaks(struct up_dev_s *priv, boolean enable)
static int up_setup(struct uart_dev_s *dev)
{
#ifdef CONFIG_SUPPRESS_UART_CONFIG
- struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
uint16 brsr;
/* Clear fifos */
@@ -292,7 +292,7 @@ static int up_setup(struct uart_dev_s *dev)
/* Set rx and tx triggers */
up_serialout(priv, UART_DM320_RFCR, UART_RFCR_RTL_1);
- up_serialout(priv, UART_DM320_TFCR, UART_TFCR_TTL_1);
+ up_serialout(priv, UART_DM320_TFCR, UART_TFCR_TTL_16);
/* Set up the MSR */
@@ -391,7 +391,7 @@ static int up_setup(struct uart_dev_s *dev)
static void up_shutdown(struct uart_dev_s *dev)
{
- struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
+ struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
up_disableuartint(priv, NULL);
}
@@ -414,7 +414,6 @@ static int up_interrupt(int irq, void *context)
struct up_dev_s *priv;
uint16 status;
int passes;
-
if (g_uart1port.irq == irq)
{
diff --git a/nuttx/drivers/serial.c b/nuttx/drivers/serial.c
index fd0e5b1b7..29bfa27d7 100644
--- a/nuttx/drivers/serial.c
+++ b/nuttx/drivers/serial.c
@@ -91,24 +91,6 @@ struct file_operations g_serialops =
************************************************************************************/
/************************************************************************************
- * Name: uart_waittxfifonotfull
- ************************************************************************************/
-
-#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_SERIAL_INTS)
-static inline void uart_waittxfifonotfull(uart_dev_t *dev)
-{
- int tmp;
- for (tmp = 1000 ; tmp > 0 ; tmp--)
- {
- if (uart_txfifonotfull(dev))
- {
- break;
- }
- }
-}
-#endif
-
-/************************************************************************************
* Name: uart_takesem
************************************************************************************/
@@ -155,23 +137,6 @@ static void uart_putxmitchar(uart_dev_t *dev, int ch)
}
else
{
-#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_SERIAL_INTS)
- /* Transfer some characters with interrupts disabled */
-
- uart_xmitchars(dev);
-
- /* If we unsuccessful in making room in the buffer.
- * then transmit the characters with interrupts
- * enabled and wait for result.
- */
-
- if (nexthead == dev->xmit.tail)
- {
- /* Still no space */
-
- uart_waittxfifonotfull(dev);
- }
-#else
/* Inform the interrupt level logic that we are waiting */
dev->xmitwaiting = TRUE;
@@ -185,7 +150,6 @@ static void uart_putxmitchar(uart_dev_t *dev, int ch)
uart_enabletxint(dev);
uart_takesem(&dev->xmitsem);
uart_disabletxint(dev);
-#endif
}
}
}
@@ -275,11 +239,7 @@ static ssize_t uart_write(struct file *filep, const char *buffer, size_t buflen)
if (dev->xmit.head != dev->xmit.tail)
{
-#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_SERIAL_INTS)
- uart_xmitchars(dev);
-#else
uart_enabletxint(dev);
-#endif
}
uart_givesem(&dev->xmit.sem);
@@ -446,10 +406,8 @@ static int uart_open(struct file *filep)
/* Attache and enabled the IRQ */
-#ifndef CONFIG_SUPPRESS_SERIAL_INTS
ret = irq_attach(dev->irq, dev->ops->handler);
if (ret == OK)
-#endif
{
/* Mark the io buffers empty */
@@ -460,9 +418,7 @@ static int uart_open(struct file *filep)
/* Finally, enable interrupts */
-#ifndef CONFIG_SUPPRESS_SERIAL_INTS
up_enable_irq(dev->irq);
-#endif
uart_enablerxint(dev);
}
irqrestore(flags);