summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80/src/common
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/z80/src/common')
-rw-r--r--nuttx/arch/z80/src/common/up_arch.h7
-rw-r--r--nuttx/arch/z80/src/common/up_assert.c8
-rw-r--r--nuttx/arch/z80/src/common/up_blocktask.c6
-rw-r--r--nuttx/arch/z80/src/common/up_createstack.c11
-rw-r--r--nuttx/arch/z80/src/common/up_doirq.c6
-rw-r--r--nuttx/arch/z80/src/common/up_exit.c4
-rw-r--r--nuttx/arch/z80/src/common/up_idle.c6
-rw-r--r--nuttx/arch/z80/src/common/up_initialize.c3
-rw-r--r--nuttx/arch/z80/src/common/up_internal.h11
-rw-r--r--nuttx/arch/z80/src/common/up_interruptcontext.c8
-rw-r--r--nuttx/arch/z80/src/common/up_puts.c1
-rw-r--r--nuttx/arch/z80/src/common/up_releasepending.c3
-rw-r--r--nuttx/arch/z80/src/common/up_releasestack.c5
-rw-r--r--nuttx/arch/z80/src/common/up_reprioritizertr.c13
-rw-r--r--nuttx/arch/z80/src/common/up_stackdump.c16
-rw-r--r--nuttx/arch/z80/src/common/up_unblocktask.c3
-rw-r--r--nuttx/arch/z80/src/common/up_usestack.c7
17 files changed, 61 insertions, 57 deletions
diff --git a/nuttx/arch/z80/src/common/up_arch.h b/nuttx/arch/z80/src/common/up_arch.h
index ff53010db..0cb523ea1 100644
--- a/nuttx/arch/z80/src/common/up_arch.h
+++ b/nuttx/arch/z80/src/common/up_arch.h
@@ -1,7 +1,7 @@
/************************************************************************************
* common/up_arch.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* 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
+ * 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.
*
@@ -41,9 +41,6 @@
************************************************************************************/
#include <nuttx/config.h>
-#ifndef __ASSEMBLY__
-# include <sys/types.h>
-#endif
#include <arch/board/board.h>
#include "chip/chip.h"
diff --git a/nuttx/arch/z80/src/common/up_assert.c b/nuttx/arch/z80/src/common/up_assert.c
index 1d8fd6a5a..9fe66ecda 100644
--- a/nuttx/arch/z80/src/common/up_assert.c
+++ b/nuttx/arch/z80/src/common/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_assert.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <stdlib.h>
#include <assert.h>
#include <debug.h>
@@ -109,7 +109,7 @@ static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
****************************************************************************/
#ifdef CONFIG_HAVE_FILENAME
-void up_assert(const ubyte *filename, int lineno)
+void up_assert(const uint8_t *filename, int lineno)
#else
void up_assert(void)
#endif
@@ -146,7 +146,7 @@ void up_assert(void)
****************************************************************************/
#ifdef CONFIG_HAVE_FILENAME
-void up_assert_code(const ubyte *filename, int lineno, int errorcode)
+void up_assert_code(const uint8_t *filename, int lineno, int errorcode)
#else
void up_assert_code(int errorcode)
#endif
diff --git a/nuttx/arch/z80/src/common/up_blocktask.c b/nuttx/arch/z80/src/common/up_blocktask.c
index 3d3ce99ad..7feb02169 100644
--- a/nuttx/arch/z80/src/common/up_blocktask.c
+++ b/nuttx/arch/z80/src/common/up_blocktask.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_blocktask.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdbool.h>
#include <sched.h>
#include <debug.h>
@@ -97,7 +97,7 @@ void up_block_task(FAR _TCB *tcb, tstate_t task_state)
else
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- boolean switch_needed;
+ bool switch_needed;
/* dbg("Blocking TCB=%p\n", tcb); */
diff --git a/nuttx/arch/z80/src/common/up_createstack.c b/nuttx/arch/z80/src/common/up_createstack.c
index 1c2d08b1f..c9da4cb9f 100644
--- a/nuttx/arch/z80/src/common/up_createstack.c
+++ b/nuttx/arch/z80/src/common/up_createstack.c
@@ -38,11 +38,14 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <nuttx/arch.h>
+
#include "up_arch.h"
#include "up_internal.h"
@@ -90,7 +93,7 @@ int up_create_stack(_TCB *tcb, size_t stack_size)
if (!tcb->stack_alloc_ptr)
{
- tcb->stack_alloc_ptr = (uint32 *)kzmalloc(stack_size);
+ tcb->stack_alloc_ptr = (uint32_t*)kzmalloc(stack_size);
}
if (tcb->stack_alloc_ptr)
@@ -105,7 +108,7 @@ int up_create_stack(_TCB *tcb, size_t stack_size)
* referenced as positive word offsets from sp.
*/
- top_of_stack = (uint32)tcb->stack_alloc_ptr + stack_size - 4;
+ top_of_stack = (uint32_t)tcb->stack_alloc_ptr + stack_size - 4;
/* The Arm7Tdmi stack must be aligned at word (4 byte)
* boundaries. If necessary top_of_stack must be rounded
@@ -113,11 +116,11 @@ int up_create_stack(_TCB *tcb, size_t stack_size)
*/
top_of_stack &= ~3;
- size_of_stack = top_of_stack - (uint32)tcb->stack_alloc_ptr + 4;
+ size_of_stack = top_of_stack - (uint32_t)tcb->stack_alloc_ptr + 4;
/* Save the adjusted stack values in the _TCB */
- tcb->adj_stack_ptr = (uint32*)top_of_stack;
+ tcb->adj_stack_ptr = (uint32_t*)top_of_stack;
tcb->adj_stack_size = size_of_stack;
up_ledon(LED_STACKCREATED);
diff --git a/nuttx/arch/z80/src/common/up_doirq.c b/nuttx/arch/z80/src/common/up_doirq.c
index fae0142eb..2c4c9e113 100644
--- a/nuttx/arch/z80/src/common/up_doirq.c
+++ b/nuttx/arch/z80/src/common/up_doirq.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_doirq.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <assert.h>
#include "up_arch.h"
@@ -70,7 +70,7 @@
* Public Functions
****************************************************************************/
-FAR chipreg_t *up_doirq(ubyte irq, FAR chipreg_t *regs)
+FAR chipreg_t *up_doirq(uint8_t irq, FAR chipreg_t *regs)
{
up_ledon(LED_INIRQ);
diff --git a/nuttx/arch/z80/src/common/up_exit.c b/nuttx/arch/z80/src/common/up_exit.c
index c9ae45bb9..da49ce377 100644
--- a/nuttx/arch/z80/src/common/up_exit.c
+++ b/nuttx/arch/z80/src/common/up_exit.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_exit.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
diff --git a/nuttx/arch/z80/src/common/up_idle.c b/nuttx/arch/z80/src/common/up_idle.c
index e2fb1e00f..550bc124d 100644
--- a/nuttx/arch/z80/src/common/up_idle.c
+++ b/nuttx/arch/z80/src/common/up_idle.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_idle.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
@@ -55,7 +55,7 @@
****************************************************************************/
#if defined(CONFIG_ARCH_LEDS) && defined(CONFIG_ARCH_BRINGUP)
-static ubyte g_ledtoggle = 0;
+static uint8_t g_ledtoggle = 0;
#endif
/****************************************************************************
diff --git a/nuttx/arch/z80/src/common/up_initialize.c b/nuttx/arch/z80/src/common/up_initialize.c
index 47c1e456e..1c71fa517 100644
--- a/nuttx/arch/z80/src/common/up_initialize.c
+++ b/nuttx/arch/z80/src/common/up_initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_initialize.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <sys/types.h>
#include <debug.h>
#include <nuttx/arch.h>
diff --git a/nuttx/arch/z80/src/common/up_internal.h b/nuttx/arch/z80/src/common/up_internal.h
index bd0917bc8..2e5afb2e3 100644
--- a/nuttx/arch/z80/src/common/up_internal.h
+++ b/nuttx/arch/z80/src/common/up_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_internal.h
*
- * Copyright (C) 2007, 2008, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,6 +55,9 @@
* Included Files
****************************************************************************/
+#include <stdint.h>
+#include <stdbool.h>
+
#include <arch/irq.h>
#include "chip/chip.h"
#include "chip/switch.h"
@@ -108,7 +111,7 @@ EXTERN void up_lowuartinit(void);
/* Defined in up_doirq.c */
-EXTERN FAR chipreg_t *up_doirq(ubyte irq, FAR chipreg_t *regs);
+EXTERN FAR chipreg_t *up_doirq(uint8_t irq, FAR chipreg_t *regs);
/* Define in up_sigdeliver */
@@ -168,7 +171,7 @@ EXTERN void up_timerhook(void);
EXTERN int up_netinitialize(void);
EXTERN void up_netuninitialize(void);
# ifdef CONFIG_ARCH_MCFILTER
-EXTERN int up_multicastfilter(FAR struct uip_driver_s *dev, FAR ubyte *mac, boolean enable);
+EXTERN int up_multicastfilter(FAR struct uip_driver_s *dev, FAR uint8_t *mac, bool enable);
# else
# define up_multicastfilter(dev, mac, enable)
# endif
@@ -180,7 +183,7 @@ EXTERN int up_multicastfilter(FAR struct uip_driver_s *dev, FAR ubyte *mac, bool
/* Return the current value of the stack pointer (used in stack dump logic) */
-EXTERN uint16 up_getsp(void);
+EXTERN uint16_t up_getsp(void);
/* Dump stack and registers */
diff --git a/nuttx/arch/z80/src/common/up_interruptcontext.c b/nuttx/arch/z80/src/common/up_interruptcontext.c
index 354227cc2..e8887abef 100644
--- a/nuttx/arch/z80/src/common/up_interruptcontext.c
+++ b/nuttx/arch/z80/src/common/up_interruptcontext.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_interruptcontext.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdbool.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
@@ -62,11 +62,11 @@
/****************************************************************************
* Name: up_interrupt_context
*
- * Description: Return TRUE is we are currently executing in
+ * Description: Return true is we are currently executing in
* the interrupt handler context.
****************************************************************************/
-boolean up_interrupt_context(void)
+bool up_interrupt_context(void)
{
return IN_INTERRUPT();
}
diff --git a/nuttx/arch/z80/src/common/up_puts.c b/nuttx/arch/z80/src/common/up_puts.c
index 1221a2466..06c38573d 100644
--- a/nuttx/arch/z80/src/common/up_puts.c
+++ b/nuttx/arch/z80/src/common/up_puts.c
@@ -38,7 +38,6 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
#include <nuttx/arch.h>
#include "up_internal.h"
diff --git a/nuttx/arch/z80/src/common/up_releasepending.c b/nuttx/arch/z80/src/common/up_releasepending.c
index bfe35d2a7..8090cb763 100644
--- a/nuttx/arch/z80/src/common/up_releasepending.c
+++ b/nuttx/arch/z80/src/common/up_releasepending.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_releasepending.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <sys/types.h>
#include <sched.h>
#include <debug.h>
diff --git a/nuttx/arch/z80/src/common/up_releasestack.c b/nuttx/arch/z80/src/common/up_releasestack.c
index 48328737c..549879725 100644
--- a/nuttx/arch/z80/src/common/up_releasestack.c
+++ b/nuttx/arch/z80/src/common/up_releasestack.c
@@ -1,7 +1,7 @@
/************************************************************
* common/up_releasestack.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -38,10 +38,11 @@
************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
#include <sched.h>
#include <debug.h>
#include <nuttx/arch.h>
+
#include "os_internal.h"
#include "up_internal.h"
diff --git a/nuttx/arch/z80/src/common/up_reprioritizertr.c b/nuttx/arch/z80/src/common/up_reprioritizertr.c
index 31fab37de..f52050033 100644
--- a/nuttx/arch/z80/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/z80/src/common/up_reprioritizertr.c
@@ -39,7 +39,8 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
#include <sched.h>
#include <debug.h>
@@ -86,7 +87,7 @@
*
****************************************************************************/
-void up_reprioritize_rtr(FAR _TCB *tcb, ubyte priority)
+void up_reprioritize_rtr(FAR _TCB *tcb, uint8_t priority)
{
/* Verify that the caller is sane */
@@ -100,12 +101,12 @@ void up_reprioritize_rtr(FAR _TCB *tcb, ubyte priority)
else
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- boolean switch_needed;
+ bool switch_needed;
slldbg("TCB=%p PRI=%d\n", tcb, priority);
/* Remove the tcb task from the ready-to-run list.
- * sched_removereadytorun will return TRUE if we just
+ * sched_removereadytorun will return true if we just
* remove the head of the ready to run list.
*/
@@ -113,10 +114,10 @@ void up_reprioritize_rtr(FAR _TCB *tcb, ubyte priority)
/* Setup up the new task priority */
- tcb->sched_priority = (ubyte)priority;
+ tcb->sched_priority = (uint8_t)priority;
/* Return the task to the specified blocked task list.
- * sched_addreadytorun will return TRUE if the task was
+ * sched_addreadytorun will return true if the task was
* added to the new list. We will need to perform a context
* switch only if the EXCLUSIVE or of the two calls is non-zero
* (i.e., one and only one the calls changes the head of the
diff --git a/nuttx/arch/z80/src/common/up_stackdump.c b/nuttx/arch/z80/src/common/up_stackdump.c
index 00c923aa9..62c4ee24c 100644
--- a/nuttx/arch/z80/src/common/up_stackdump.c
+++ b/nuttx/arch/z80/src/common/up_stackdump.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_stackdump.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <debug.h>
#include "up_arch.h"
@@ -80,9 +80,9 @@
static void up_stackdump(void)
{
_TCB *rtcb = (_TCB*)g_readytorun.head;
- uint16 sp = up_getsp();
- uint16 stack_base = (uint16)rtcb->adj_stack_ptr;
- uint16 stack_size = (uint16)rtcb->adj_stack_size;
+ uint16_t) sp = up_getsp();
+ uint16_t) stack_base = (uint16_t))rtcb->adj_stack_ptr;
+ uint16_t) stack_size = (uint16_t))rtcb->adj_stack_size;
lldbg("stack_base: %04x\n", stack_base);
lldbg("stack_size: %04x\n", stack_size);
@@ -95,11 +95,11 @@ static void up_stackdump(void)
}
else
{
- uint16 stack = sp & ~0x0f;
+ uint16_t) stack = sp & ~0x0f;
- for (stack = sp & ~0x0f; stack < stack_base; stack += 8*sizeof(uint16))
+ for (stack = sp & ~0x0f; stack < stack_base; stack += 8*sizeof(uint16_t)))
{
- uint16 *ptr = (uint16*)stack;
+ uint16_t) *ptr = (uint16_t)*)stack;
lldbg("%04x: %04x %04x %04x %04x %04x %04x %04x %04x\n",
stack, ptr[0], ptr[1], ptr[2], ptr[3],
ptr[4], ptr[5], ptr[6], ptr[7]);
diff --git a/nuttx/arch/z80/src/common/up_unblocktask.c b/nuttx/arch/z80/src/common/up_unblocktask.c
index aa09342c6..33d98e864 100644
--- a/nuttx/arch/z80/src/common/up_unblocktask.c
+++ b/nuttx/arch/z80/src/common/up_unblocktask.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/common/up_unblocktask.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <sys/types.h>
#include <sched.h>
#include <debug.h>
diff --git a/nuttx/arch/z80/src/common/up_usestack.c b/nuttx/arch/z80/src/common/up_usestack.c
index c73e99bc1..7f22e9ce6 100644
--- a/nuttx/arch/z80/src/common/up_usestack.c
+++ b/nuttx/arch/z80/src/common/up_usestack.c
@@ -38,11 +38,14 @@
************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
#include <nuttx/kmalloc.h>
#include <nuttx/arch.h>
+
#include "up_internal.h"
/************************************************************
@@ -99,7 +102,7 @@ int up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
* referenced as positive word offsets from sp.
*/
- top_of_stack = (uint32)tcb->stack_alloc_ptr + stack_size - 4;
+ top_of_stack = (uint32_t)tcb->stack_alloc_ptr + stack_size - 4;
/* The Arm7Tdmi stack must be aligned at word (4 byte)
* boundaries. If necessary top_of_stack must be rounded
@@ -107,7 +110,7 @@ int up_use_stack(_TCB *tcb, void *stack, size_t stack_size)
*/
top_of_stack &= ~3;
- size_of_stack = top_of_stack - (uint32)tcb->stack_alloc_ptr + 4;
+ size_of_stack = top_of_stack - (uint32_t)tcb->stack_alloc_ptr + 4;
/* Save the adjusted stack values in the _TCB */