summaryrefslogtreecommitdiff
path: root/nuttx/arch/c5471/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-08 15:23:56 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-03-08 15:23:56 +0000
commit77f556a36f68292909cd98a7ddeb58c3f739f324 (patch)
treefaebbaa384049b9ddfb7279ff879ef3c76f625ac /nuttx/arch/c5471/src
parent2ec8b9a0f5c8b7e7590cc5a7cc793eb249f449fe (diff)
downloadpx4-nuttx-77f556a36f68292909cd98a7ddeb58c3f739f324.tar.gz
px4-nuttx-77f556a36f68292909cd98a7ddeb58c3f739f324.tar.bz2
px4-nuttx-77f556a36f68292909cd98a7ddeb58c3f739f324.zip
Add support for onboard LEDs; Fix serial bug
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@43 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/c5471/src')
-rw-r--r--nuttx/arch/c5471/src/Makefile2
-rw-r--r--nuttx/arch/c5471/src/up_allocateheap.c5
-rw-r--r--nuttx/arch/c5471/src/up_assert.c16
-rw-r--r--nuttx/arch/c5471/src/up_createstack.c1
-rw-r--r--nuttx/arch/c5471/src/up_doirq.c2
-rw-r--r--nuttx/arch/c5471/src/up_head.S20
-rw-r--r--nuttx/arch/c5471/src/up_initialize.c1
-rw-r--r--nuttx/arch/c5471/src/up_internal.h26
-rw-r--r--nuttx/arch/c5471/src/up_leds.c107
-rw-r--r--nuttx/arch/c5471/src/up_serial.c65
-rw-r--r--nuttx/arch/c5471/src/up_sigdeliver.c2
11 files changed, 205 insertions, 42 deletions
diff --git a/nuttx/arch/c5471/src/Makefile b/nuttx/arch/c5471/src/Makefile
index a7867f0b7..ec91753fa 100644
--- a/nuttx/arch/c5471/src/Makefile
+++ b/nuttx/arch/c5471/src/Makefile
@@ -51,7 +51,7 @@ CSRCS = up_initialize.c up_initialstate.c up_idle.c up_doirq.c \
up_exit.c up_assert.c up_blocktask.c up_unblocktask.c \
up_releasepending.c up_reprioritizertr.c up_copystate.c \
up_schedulesigaction.c up_sigdeliver.c up_serial.c \
- up_delay.c up_allocateheap.c
+ up_delay.c up_allocateheap.c up_leds.c
COBJS = $(CSRCS:.c=.o)
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/arch/c5471/src/up_allocateheap.c b/nuttx/arch/c5471/src/up_allocateheap.c
index 2d40857f8..3ee7a6820 100644
--- a/nuttx/arch/c5471/src/up_allocateheap.c
+++ b/nuttx/arch/c5471/src/up_allocateheap.c
@@ -72,6 +72,7 @@
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
{
- *heap_start = (FAR void*)g_heapstart;
- *heap_size = CONFIG_DRAM_END - g_heapstart;
+ up_ledon(LED_HEAPALLOCATE);
+ *heap_start = (FAR void*)g_heapbase;
+ *heap_size = CONFIG_DRAM_END - g_heapbase;
}
diff --git a/nuttx/arch/c5471/src/up_assert.c b/nuttx/arch/c5471/src/up_assert.c
index 49754088a..679a01f29 100644
--- a/nuttx/arch/c5471/src/up_assert.c
+++ b/nuttx/arch/c5471/src/up_assert.c
@@ -65,7 +65,15 @@ static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
if (current_regs || ((_TCB*)g_readytorun.head)->pid == 0)
{
(void)irqsave();
- for(;;);
+ for(;;)
+ {
+#ifdef CONFIG_C5471_LEDS
+ up_ledon(LED_PANIC);
+ up_delay(250);
+ up_ledoff(LED_PANIC);
+ up_delay(250);
+#endif
+ }
}
else
{
@@ -83,8 +91,9 @@ static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
void up_assert(const ubyte *filename, int lineno)
{
+ up_ledon(LED_ASSERTION);
dbg("Assertion failed at file:%s line: %d\n",
- filename, lineno);
+ filename, lineno);
_up_assert(EXIT_FAILURE);
}
@@ -94,7 +103,8 @@ void up_assert(const ubyte *filename, int lineno)
void up_assert_code(const ubyte *filename, int lineno, int errorcode)
{
+ up_ledon(LED_ASSERTION);
dbg("Assertion failed at file:%s line: %d error code: %d\n",
- filename, lineno, errorcode);
+ filename, lineno, errorcode);
_up_assert(errorcode);
}
diff --git a/nuttx/arch/c5471/src/up_createstack.c b/nuttx/arch/c5471/src/up_createstack.c
index 0e1f0690a..7903ee8b8 100644
--- a/nuttx/arch/c5471/src/up_createstack.c
+++ b/nuttx/arch/c5471/src/up_createstack.c
@@ -119,6 +119,7 @@ STATUS up_create_stack(_TCB *tcb, size_t stack_size)
tcb->adj_stack_ptr = (uint32*)top_of_stack;
tcb->adj_stack_size = size_of_stack;
+ up_ledon(LED_STACKCREATED);
return OK;
}
diff --git a/nuttx/arch/c5471/src/up_doirq.c b/nuttx/arch/c5471/src/up_doirq.c
index 48cbd3e4a..f4e07873c 100644
--- a/nuttx/arch/c5471/src/up_doirq.c
+++ b/nuttx/arch/c5471/src/up_doirq.c
@@ -68,6 +68,7 @@
void up_doirq(int irq, uint32* regs)
{
+ up_ledon(LED_INIRQ);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
PANIC(OSERR_ERREXCEPTION);
#else
@@ -85,5 +86,6 @@ void up_doirq(int irq, uint32* regs)
up_enable_irq(irq);
}
+ up_ledoff(LED_INIRQ);
#endif
}
diff --git a/nuttx/arch/c5471/src/up_head.S b/nuttx/arch/c5471/src/up_head.S
index dd59b98b7..770caddce 100644
--- a/nuttx/arch/c5471/src/up_head.S
+++ b/nuttx/arch/c5471/src/up_head.S
@@ -38,10 +38,11 @@
************************************************************/
#include <nuttx/config.h>
+#include "up_internal.h"
#include "c5471.h"
/************************************************************
- * Definitions
+ * Macros
************************************************************/
/* This macro will modify r0, r1, r2 and r14 */
@@ -114,6 +115,11 @@ __start:
mov r0, #'\n'
bl up_putc
#endif
+ /* Initialize onboard LEDs */
+
+#ifdef CONFIG_C5471_LEDS
+ bl up_ledinit
+#endif
/* Then jump to OS entry */
@@ -124,7 +130,7 @@ __start:
* _ebss is the end of the BSS regsion (see ld.script)
* The idle task stack starts at the end of BSS and is
* of size CONFIG_PROC_STACK_SIZE. The heap continues
- * from there until the end of memory. See g_heapstart
+ * from there until the end of memory. See g_heapbase
* below.
*/
@@ -139,18 +145,18 @@ LC2: .long _eronly /* Where .data defaults are stored in FLASH */
#endif
.size __start, .-__start
- /* This global variable is unsigned long g_heapstart and is
+ /* This global variable is unsigned long g_heapbase and is
* exported from here only because of its coupling to LCO
* above.
*/
.data
.align 4
- .globl g_heapstart
- .type g_heapstart, object
-g_heapstart:
+ .globl g_heapbase
+ .type g_heapbase, object
+g_heapbase:
.long _ebss+CONFIG_PROC_STACK_SIZE
- .size g_heapstart, .-g_heapstart
+ .size g_heapbase, .-g_heapbase
.end
diff --git a/nuttx/arch/c5471/src/up_initialize.c b/nuttx/arch/c5471/src/up_initialize.c
index 86b6a9f8d..6ae3f0de3 100644
--- a/nuttx/arch/c5471/src/up_initialize.c
+++ b/nuttx/arch/c5471/src/up_initialize.c
@@ -99,4 +99,5 @@ void up_initialize(void)
/* Initialize the serial device driver */
up_serialinit();
+ up_ledon(LED_IRQSENABLED);
}
diff --git a/nuttx/arch/c5471/src/up_internal.h b/nuttx/arch/c5471/src/up_internal.h
index 0c03967c0..5f7e4307e 100644
--- a/nuttx/arch/c5471/src/up_internal.h
+++ b/nuttx/arch/c5471/src/up_internal.h
@@ -48,6 +48,18 @@
#define CONFIG_SUPPRESS_INTERRUPTS 1 /* Do not enable interrupts */
#undef CONFIG_SUPPRESS_UART_CONFIG /* Do not reconfig UART */
+#define CONFIG_C5471_LEDS 1 /* Use LEDs to show state */
+
+/* LED meanings */
+
+#define LED_STARTED 0
+#define LED_HEAPALLOCATE 1
+#define LED_IRQSENABLED 2
+#define LED_STACKCREATED 3
+#define LED_INIRQ 4
+#define LED_SIGNAL 5
+#define LED_ASSERTION 6
+#define LED_PANIC 7
/************************************************************
* Public Types
@@ -75,7 +87,7 @@ extern uint32 *current_regs;
* CONFIG_DRAM_END
*/
-extern uint32 g_heapstart;
+extern uint32 g_heapbase;
#endif
/************************************************************
@@ -133,6 +145,18 @@ extern void up_timerinit(void);
extern void up_maskack_irq(int irq);
+/* Defined in up_leds.c */
+
+#ifdef CONFIG_C5471_LEDS
+extern void up_ledinit(void);
+extern void up_ledon(int led);
+extern void up_ledoff(int led);
+#else
+# define up_ledinit()
+# define up_ledon(led)
+# define up_ledoff(led)
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __UP_INTERNAL_H */
diff --git a/nuttx/arch/c5471/src/up_leds.c b/nuttx/arch/c5471/src/up_leds.c
new file mode 100644
index 000000000..ee1241ede
--- /dev/null
+++ b/nuttx/arch/c5471/src/up_leds.c
@@ -0,0 +1,107 @@
+/************************************************************
+ * up_leds.c
+ *
+ * Copyright (C) 2007 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 Gregory Nutt 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 <sys/types.h>
+#include "up_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+#define CS2 *(volatile uint32*)0xffff2e08
+#define LEDS *(volatile uint32*)0x01000000
+
+/************************************************************
+ * Private Data
+ ************************************************************/
+
+static uint32 g_ledstate;
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Funtions
+ ************************************************************/
+
+/************************************************************
+ * Name: up_ledinit
+ ************************************************************/
+
+#ifdef CONFIG_C5471_LEDS
+void up_ledinit(void)
+{
+ /* Enable acces to LEDs */
+
+ CS2 = 0x000013db;
+
+ /* Turn LED 1-7 off; turn LED 0 on */
+
+ g_ledstate = 0x000000fe;
+ LEDS = g_ledstate;
+}
+
+/************************************************************
+ * Name: up_ledon
+ ************************************************************/
+
+void up_ledon(int led)
+{
+ if (led < 8)
+ {
+ g_ledstate &= ~(1 << led);
+ LEDS = g_ledstate;
+ }
+}
+
+/************************************************************
+ * Name: up_ledoff
+ ************************************************************/
+
+void up_ledoff(int led)
+{
+ if (led < 8)
+ {
+ g_ledstate |= (1 << led);
+ LEDS = g_ledstate;
+ }
+}
+#endif /* CONFIG_C5471_LEDS */
diff --git a/nuttx/arch/c5471/src/up_serial.c b/nuttx/arch/c5471/src/up_serial.c
index faaf7aeed..b51e48c0e 100644
--- a/nuttx/arch/c5471/src/up_serial.c
+++ b/nuttx/arch/c5471/src/up_serial.c
@@ -589,42 +589,51 @@ static void up_xmitchars(up_dev_t *dev)
static void up_putxmitchar(up_dev_t *dev, int ch)
{
int nexthead = dev->xmit.head + 1;
- if (nexthead >= dev->xmit.size)
- {
- nexthead = 0;
- }
- if (nexthead != dev->xmit.tail)
+ for(;;)
{
- dev->xmit.buffer[dev->xmit.head] = ch;
- dev->xmit.head = nexthead;
- }
- else
- {
- /* Transfer some characters with interrupts disabled */
-
- up_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.size)
+ {
+ nexthead = 0;
+ }
- if (nexthead == dev->xmit.tail)
+ if (nexthead != dev->xmit.tail)
{
- /* Still no space */
+ dev->xmit.buffer[dev->xmit.head] = ch;
+ dev->xmit.head = nexthead;
+ return;
+ }
+ else
+ {
+ /* Transfer some characters with interrupts disabled */
- dev->xmitwaiting = TRUE;
+ up_xmitchars(dev);
- /* Wait for some characters to be sent from the buffer
- * with the TX interrupt disabled.
+ /* If we unsuccessful in making room in the buffer.
+ * then transmit the characters with interrupts
+ * enabled and wait for result.
*/
- up_enabletxint(dev);
- up_takesem(&dev->xmitsem);
- up_disabletxint(dev);
- }
- }
+ if (nexthead == dev->xmit.tail)
+ {
+ /* Still no space */
+
+#ifdef CONFIG_SUPPRESS_INTERRUPTS
+ up_waittxfifonotfull(dev);
+#else
+ dev->xmitwaiting = TRUE;
+
+ /* Wait for some characters to be sent from the buffer
+ * with the TX interrupt disabled.
+ */
+
+ up_enabletxint(dev);
+ up_takesem(&dev->xmitsem);
+ up_disabletxint(dev);
+#endif
+ }
+ }
+ }
}
/************************************************************
diff --git a/nuttx/arch/c5471/src/up_sigdeliver.c b/nuttx/arch/c5471/src/up_sigdeliver.c
index 1ef77c182..df1040314 100644
--- a/nuttx/arch/c5471/src/up_sigdeliver.c
+++ b/nuttx/arch/c5471/src/up_sigdeliver.c
@@ -80,6 +80,7 @@ void up_sigdeliver(void)
uint32 regs[XCPTCONTEST_REGS];
sig_deliver_t sigdeliver;
+ up_ledon(LED_SIGNAL);
ASSERT(rtcb->xcp.sigdeliver);
/* Save the real return state on the stack. */
@@ -113,5 +114,6 @@ void up_sigdeliver(void)
* execution.
*/
+ up_ledoff(LED_SIGNAL);
up_fullcontextrestore(regs);
}