summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/sh/include/m16c/irq.h8
-rw-r--r--nuttx/arch/sh/include/sh1/irq.h16
-rw-r--r--nuttx/arch/sh/src/common/up_arch.h16
-rw-r--r--nuttx/arch/sh/src/common/up_assert.c8
-rw-r--r--nuttx/arch/sh/src/common/up_blocktask.c8
-rw-r--r--nuttx/arch/sh/src/common/up_createstack.c9
-rw-r--r--nuttx/arch/sh/src/common/up_doirq.c11
-rw-r--r--nuttx/arch/sh/src/common/up_exit.c6
-rw-r--r--nuttx/arch/sh/src/common/up_idle.c4
-rw-r--r--nuttx/arch/sh/src/common/up_initialize.c3
-rw-r--r--nuttx/arch/sh/src/common/up_internal.h30
-rw-r--r--nuttx/arch/sh/src/common/up_interruptcontext.c10
-rw-r--r--nuttx/arch/sh/src/common/up_lowputs.c3
-rw-r--r--nuttx/arch/sh/src/common/up_puts.c3
-rw-r--r--nuttx/arch/sh/src/common/up_releasepending.c5
-rw-r--r--nuttx/arch/sh/src/common/up_releasestack.c5
-rw-r--r--nuttx/arch/sh/src/common/up_reprioritizertr.c15
-rw-r--r--nuttx/arch/sh/src/common/up_unblocktask.c5
-rw-r--r--nuttx/arch/sh/src/common/up_usestack.c8
-rw-r--r--nuttx/arch/sh/src/m16c/chip.h30
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_copystate.c4
-rwxr-xr-xnuttx/arch/sh/src/m16c/m16c_dumpstate.c34
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_initialstate.c15
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_irq.c4
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_lowputc.c8
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c10
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_serial.c120
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_sigdeliver.c4
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_timer.h1
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_timerisr.c5
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_uart.h1
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_vectors.S4
-rw-r--r--nuttx/arch/sh/src/sh1/chip.h6
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_703x.h3
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_copystate.c6
-rwxr-xr-xnuttx/arch/sh/src/sh1/sh1_dumpstate.c34
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_initialstate.c8
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_irq.c14
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_lowputc.c8
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_schedulesigaction.c8
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_serial.c86
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_sigdeliver.c6
-rw-r--r--nuttx/arch/sh/src/sh1/sh1_timerisr.c12
43 files changed, 318 insertions, 286 deletions
diff --git a/nuttx/arch/sh/include/m16c/irq.h b/nuttx/arch/sh/include/m16c/irq.h
index dc7a43693..ad7e43ad9 100644
--- a/nuttx/arch/sh/include/m16c/irq.h
+++ b/nuttx/arch/sh/include/m16c/irq.h
@@ -45,7 +45,7 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
/************************************************************************************
* Definitions
@@ -249,13 +249,13 @@ struct xcptcontext
/* These are saved copies of LR and SR used during signal processing. */
- ubyte saved_pc[2];
- ubyte saved_flg;
+ uint8_t saved_pc[2];
+ uint8_t saved_flg;
#endif
/* Register save area */
- ubyte regs[XCPTCONTEXT_SIZE];
+ uint8_t regs[XCPTCONTEXT_SIZE];
};
#endif
diff --git a/nuttx/arch/sh/include/sh1/irq.h b/nuttx/arch/sh/include/sh1/irq.h
index 26155864a..5e21ecc6b 100644
--- a/nuttx/arch/sh/include/sh1/irq.h
+++ b/nuttx/arch/sh/include/sh1/irq.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/sh/include/sh1/irq.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
@@ -45,7 +45,7 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
/************************************************************************************
* Definitions
@@ -264,7 +264,7 @@
* of the corresponding vector in the vector table.
*
* These offsets are specified as a vector number (suitably for indexing an array
- * of uint32) but would have to by multiplied by 4 to get an addressable, byte
+ * of uint32_t) but would have to by multiplied by 4 to get an addressable, byte
* offset.
*/
@@ -468,13 +468,13 @@ struct xcptcontext
/* These are saved copies of LR and SR used during signal processing. */
- uint32 saved_pc;
- uint32 saved_sr;
+ uint32_t saved_pc;
+ uint32_t saved_sr;
#endif
/* Register save area */
- uint32 regs[XCPTCONTEXT_REGS];
+ uint32_t regs[XCPTCONTEXT_REGS];
};
#endif
@@ -526,14 +526,14 @@ static inline irqstate_t irqsave(void)
static inline void irqdisable(void)
{
- uint32 flags = __getsr();
+ uint32_t flags = __getsr();
__setsr(flags | 0x000000f0);
}
/* Enable IRQs */
static inline void irqenable(void)
{
- uint32 flags = __getsr();
+ uint32_t flags = __getsr();
__setsr(flags & ~0x000000f0);
}
diff --git a/nuttx/arch/sh/src/common/up_arch.h b/nuttx/arch/sh/src/common/up_arch.h
index ae94c03f8..ddc66fb76 100644
--- a/nuttx/arch/sh/src/common/up_arch.h
+++ b/nuttx/arch/sh/src/common/up_arch.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_arch.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
@@ -42,7 +42,7 @@
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
-# include <sys/types.h>
+# include <stdint.h>
#endif
#include <arch/board/board.h>
@@ -58,12 +58,12 @@
#ifndef __ASSEMBLY__
-# define getreg8(a) (*(volatile ubyte *)(a))
-# define putreg8(v,a) (*(volatile ubyte *)(a) = (v))
-# define getreg16(a) (*(volatile uint16 *)(a))
-# define putreg16(v,a) (*(volatile uint16 *)(a) = (v))
-# define getreg32(a) (*(volatile uint32 *)(a))
-# define putreg32(v,a) (*(volatile uint32 *)(a) = (v))
+# define getreg8(a) (*(volatile uint8_t *)(a))
+# define putreg8(v,a) (*(volatile uint8_t *)(a) = (v))
+# define getreg16(a) (*(volatile uint16_t *)(a))
+# define putreg16(v,a) (*(volatile uint16_t *)(a) = (v))
+# define getreg32(a) (*(volatile uint32_t *)(a))
+# define putreg32(v,a) (*(volatile uint32_t *)(a) = (v))
#endif
diff --git a/nuttx/arch/sh/src/common/up_assert.c b/nuttx/arch/sh/src/common/up_assert.c
index 3cac6606f..95b87af6f 100644
--- a/nuttx/arch/sh/src/common/up_assert.c
+++ b/nuttx/arch/sh/src/common/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_assert.c
*
- * 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
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <stdlib.h>
#include <assert.h>
#include <debug.h>
@@ -107,7 +107,7 @@ static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
* Name: up_assert
****************************************************************************/
-void up_assert(const ubyte *filename, int lineno)
+void up_assert(const uint8_t *filename, int lineno)
{
#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG)
_TCB *rtcb = (_TCB*)g_readytorun.head;
@@ -129,7 +129,7 @@ void up_assert(const ubyte *filename, int lineno)
* Name: up_assert_code
****************************************************************************/
-void up_assert_code(const ubyte *filename, int lineno, int errorcode)
+void up_assert_code(const uint8_t *filename, int lineno, int errorcode)
{
#if CONFIG_TASK_NAME_SIZE > 0 && defined(CONFIG_DEBUG)
_TCB *rtcb = (_TCB*)g_readytorun.head;
diff --git a/nuttx/arch/sh/src/common/up_blocktask.c b/nuttx/arch/sh/src/common/up_blocktask.c
index 547fd368f..dc8c1a1fa 100644
--- a/nuttx/arch/sh/src/common/up_blocktask.c
+++ b/nuttx/arch/sh/src/common/up_blocktask.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_blocktask.c
*
- * 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
@@ -38,10 +38,12 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
+#include <stdbool.h>
#include <sched.h>
#include <debug.h>
#include <nuttx/arch.h>
+
#include "os_internal.h"
#include "up_internal.h"
@@ -93,7 +95,7 @@ void up_block_task(_TCB *tcb, tstate_t task_state)
else
{
_TCB *rtcb = (_TCB*)g_readytorun.head;
- boolean switch_needed;
+ bool switch_needed;
/* Remove the tcb task from the ready-to-run list. If we
* are blocking the task at the head of the task list (the
diff --git a/nuttx/arch/sh/src/common/up_createstack.c b/nuttx/arch/sh/src/common/up_createstack.c
index 853601726..35651fe86 100644
--- a/nuttx/arch/sh/src/common/up_createstack.c
+++ b/nuttx/arch/sh/src/common/up_createstack.c
@@ -40,6 +40,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
@@ -93,7 +94,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)
@@ -108,7 +109,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
@@ -116,11 +117,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/sh/src/common/up_doirq.c b/nuttx/arch/sh/src/common/up_doirq.c
index aa938be18..33d33a052 100644
--- a/nuttx/arch/sh/src/common/up_doirq.c
+++ b/nuttx/arch/sh/src/common/up_doirq.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_doirq.c
*
- * 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
@@ -38,10 +38,13 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
+#include <stdin.h>
+#include <assert.h>
+
#include <nuttx/irq.h>
#include <nuttx/arch.h>
-#include <assert.h>
+
#include "up_arch.h"
#include "os_internal.h"
#include "up_internal.h"
@@ -66,7 +69,7 @@
* Public Functions
****************************************************************************/
-uint32 *up_doirq(int irq, uint32* regs)
+uint32_t *up_doirq(int irq, uint32_t* regs)
{
up_ledon(LED_INIRQ);
#ifdef CONFIG_SUPPRESS_INTERRUPTS
diff --git a/nuttx/arch/sh/src/common/up_exit.c b/nuttx/arch/sh/src/common/up_exit.c
index ede048370..29213ce9d 100644
--- a/nuttx/arch/sh/src/common/up_exit.c
+++ b/nuttx/arch/sh/src/common/up_exit.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_exit.c
*
- * 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
@@ -38,10 +38,12 @@
****************************************************************************/
#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/sh/src/common/up_idle.c b/nuttx/arch/sh/src/common/up_idle.c
index a1a63dd43..f95f019ae 100644
--- a/nuttx/arch/sh/src/common/up_idle.c
+++ b/nuttx/arch/sh/src/common/up_idle.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_idle.c
*
- * 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
@@ -38,8 +38,8 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
#include <nuttx/arch.h>
+
#include "up_internal.h"
/****************************************************************************
diff --git a/nuttx/arch/sh/src/common/up_initialize.c b/nuttx/arch/sh/src/common/up_initialize.c
index 114c8df98..1b4ceb8be 100644
--- a/nuttx/arch/sh/src/common/up_initialize.c
+++ b/nuttx/arch/sh/src/common/up_initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_initialize.c
*
- * 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
@@ -39,7 +39,6 @@
#include <nuttx/config.h>
-#include <sys/types.h>
#include <debug.h>
#include <nuttx/arch.h>
diff --git a/nuttx/arch/sh/src/common/up_internal.h b/nuttx/arch/sh/src/common/up_internal.h
index 27205c239..7840caf66 100644
--- a/nuttx/arch/sh/src/common/up_internal.h
+++ b/nuttx/arch/sh/src/common/up_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_internal.h
*
- * Copyright (C) 2008, 2009 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
@@ -40,6 +40,10 @@
* Included Files
****************************************************************************/
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -94,7 +98,7 @@ typedef void (*up_vector_t)(void);
* interrupt processing.
*/
-extern uint32 *current_regs;
+extern uint32_t *current_regs;
/* This is the beginning of heap as provided from up_head.S.
* This is the first address in DRAM after the loaded
@@ -102,7 +106,7 @@ extern uint32 *current_regs;
* CONFIG_DRAM_END
*/
-extern uint32 g_heapbase;
+extern uint32_t g_heapbase;
#endif
/****************************************************************************
@@ -118,18 +122,18 @@ extern uint32 g_heapbase;
/* Defined in files with the same name as the function */
extern void up_boot(void);
-extern void up_copystate(uint32 *dest, uint32 *src);
-extern void up_dataabort(uint32 *regs);
-extern void up_decodeirq(uint32 *regs);
-extern uint32 *up_doirq(int irq, uint32 *regs);
-extern void up_fullcontextrestore(uint32 *regs) __attribute__ ((noreturn));
+extern void up_copystate(uint32_t *dest, uint32_t *src);
+extern void up_dataabort(uint32_t *regs);
+extern void up_decodeirq(uint32_t *regs);
+extern uint32_t *up_doirq(int irq, uint32_t *regs);
+extern void up_fullcontextrestore(uint32_t *regs) __attribute__ ((noreturn));
extern void up_irqinitialize(void);
-extern void up_prefetchabort(uint32 *regs);
-extern int up_saveusercontext(uint32 *regs);
+extern void up_prefetchabort(uint32_t *regs);
+extern int up_saveusercontext(uint32_t *regs);
extern void up_sigdeliver(void);
-extern void up_syscall(uint32 *regs);
-extern int up_timerisr(int irq, uint32 *regs);
-extern void up_undefinedinsn(uint32 *regs);
+extern void up_syscall(uint32_t *regs);
+extern int up_timerisr(int irq, uint32_t *regs);
+extern void up_undefinedinsn(uint32_t *regs);
extern void up_lowputc(char ch);
extern void up_puts(const char *str);
extern void up_lowputs(const char *str);
diff --git a/nuttx/arch/sh/src/common/up_interruptcontext.c b/nuttx/arch/sh/src/common/up_interruptcontext.c
index aa2720aa8..16b443619 100644
--- a/nuttx/arch/sh/src/common/up_interruptcontext.c
+++ b/nuttx/arch/sh/src/common/up_interruptcontext.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_interruptcontext.c
*
- * 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
@@ -38,9 +38,11 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
+#include <stdbool.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
+
#include "up_internal.h"
/****************************************************************************
@@ -58,11 +60,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 current_regs != NULL;
}
diff --git a/nuttx/arch/sh/src/common/up_lowputs.c b/nuttx/arch/sh/src/common/up_lowputs.c
index 78ed1fef6..54438835d 100644
--- a/nuttx/arch/sh/src/common/up_lowputs.c
+++ b/nuttx/arch/sh/src/common/up_lowputs.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_lowputs.c
*
- * 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
@@ -38,7 +38,6 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
#include "up_internal.h"
diff --git a/nuttx/arch/sh/src/common/up_puts.c b/nuttx/arch/sh/src/common/up_puts.c
index 2e6e22e48..d22b22e71 100644
--- a/nuttx/arch/sh/src/common/up_puts.c
+++ b/nuttx/arch/sh/src/common/up_puts.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_puts.c
*
- * 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
@@ -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/sh/src/common/up_releasepending.c b/nuttx/arch/sh/src/common/up_releasepending.c
index ff5f17ccf..2f54e0249 100644
--- a/nuttx/arch/sh/src/common/up_releasepending.c
+++ b/nuttx/arch/sh/src/common/up_releasepending.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_releasepending.c
*
- * 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
@@ -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/sh/src/common/up_releasestack.c b/nuttx/arch/sh/src/common/up_releasestack.c
index 729d7791a..b8c9fb8bb 100644
--- a/nuttx/arch/sh/src/common/up_releasestack.c
+++ b/nuttx/arch/sh/src/common/up_releasestack.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_releasestack.c
*
- * 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
@@ -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/sh/src/common/up_reprioritizertr.c b/nuttx/arch/sh/src/common/up_reprioritizertr.c
index be465fd0a..cc9d0ff47 100644
--- a/nuttx/arch/sh/src/common/up_reprioritizertr.c
+++ b/nuttx/arch/sh/src/common/up_reprioritizertr.c
@@ -38,10 +38,13 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
+#include <stdint.h>
+#include <stdbool.h>
#include <sched.h>
#include <debug.h>
#include <nuttx/arch.h>
+
#include "os_internal.h"
#include "up_internal.h"
@@ -81,7 +84,7 @@
*
****************************************************************************/
-void up_reprioritize_rtr(_TCB *tcb, ubyte priority)
+void up_reprioritize_rtr(_TCB *tcb, uint8_t priority)
{
/* Verify that the caller is sane */
@@ -95,12 +98,12 @@ void up_reprioritize_rtr(_TCB *tcb, ubyte priority)
else
{
_TCB *rtcb = (_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.
*/
@@ -108,10 +111,10 @@ void up_reprioritize_rtr(_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/sh/src/common/up_unblocktask.c b/nuttx/arch/sh/src/common/up_unblocktask.c
index c70549953..6421c5619 100644
--- a/nuttx/arch/sh/src/common/up_unblocktask.c
+++ b/nuttx/arch/sh/src/common/up_unblocktask.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/common/up_unblocktask.c
*
- * 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
@@ -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 "clock_internal.h"
#include "up_internal.h"
diff --git a/nuttx/arch/sh/src/common/up_usestack.c b/nuttx/arch/sh/src/common/up_usestack.c
index 226d5f52f..6b472b8a2 100644
--- a/nuttx/arch/sh/src/common/up_usestack.c
+++ b/nuttx/arch/sh/src/common/up_usestack.c
@@ -38,11 +38,15 @@
****************************************************************************/
#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 +103,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 +111,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 */
diff --git a/nuttx/arch/sh/src/m16c/chip.h b/nuttx/arch/sh/src/m16c/chip.h
index 095bb688c..32d04b26e 100644
--- a/nuttx/arch/sh/src/m16c/chip.h
+++ b/nuttx/arch/sh/src/m16c/chip.h
@@ -41,7 +41,9 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
/************************************************************************************
* Definitions
@@ -251,26 +253,26 @@
#ifndef __ASSEMBLY__
-extern uint16 g_snbss; /* Start of near .bss */
-extern uint16 g_enbss; /* End+1 of near .bss */
-extern uint16 g_sndata; /* Start of near .data */
-extern uint16 g_endata; /* End+1 of near .data */
-extern uint32 g_enronly; /* Start of relocated read-only data in FLASH */
+extern uint16_t g_snbss; /* Start of near .bss */
+extern uint16_t g_enbss; /* End+1 of near .bss */
+extern uint16_t g_sndata; /* Start of near .data */
+extern uint16_t g_endata; /* End+1 of near .data */
+extern uint32_t g_enronly; /* Start of relocated read-only data in FLASH */
#ifdef CONFIG_M16C_HAVEFARRAM
- extern uint32 g_sfbss; /* Start of far .bss */
- extern uint32 g_efbss; /* End+1 of far .bss */
- extern uint32 g_sfdata; /* Start of far .data */
- extern uint32 g_efdata; /* End_1 of far .data */
- xtern uint32 g_efronly; /* Start of relocated read-only data in FLASH */
+ extern uint32_t g_sfbss; /* Start of far .bss */
+ extern uint32_t g_efbss; /* End+1 of far .bss */
+ extern uint32_t g_sfdata; /* Start of far .data */
+ extern uint32_t g_efdata; /* End_1 of far .data */
+ extern uint32_t g_efronly; /* Start of relocated read-only data in FLASH */
#endif
-extern uint32 g_svarvect; /* Start of variable vectors */
-extern uint32 g_heapbase; /* Start of the heap */
+extern uint32_t g_svarvect; /* Start of variable vectors */
+extern uint32_t g_heapbase; /* Start of the heap */
/* Address of the saved user stack pointer */
#ifndef __ASSEMBLY__
# if CONFIG_ARCH_INTERRUPTSTACK > 3
- extern uint16 g_userstack;
+ extern uint16_t g_userstack;
# endif
#endif
diff --git a/nuttx/arch/sh/src/m16c/m16c_copystate.c b/nuttx/arch/sh/src/m16c/m16c_copystate.c
index c74b57675..3c1748549 100644
--- a/nuttx/arch/sh/src/m16c/m16c_copystate.c
+++ b/nuttx/arch/sh/src/m16c/m16c_copystate.c
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <string.h>
#include "os_internal.h"
@@ -67,7 +67,7 @@
/* A little faster than most memcpy's */
-void up_copystate(uint32 *dest, uint32 *src)
+void up_copystate(uint32_t *dest, uint32_t *src)
{
memcpy(dest, src, XCPTCONTEXT_SIZE);
}
diff --git a/nuttx/arch/sh/src/m16c/m16c_dumpstate.c b/nuttx/arch/sh/src/m16c/m16c_dumpstate.c
index 11bd990cd..ff451e9b4 100755
--- a/nuttx/arch/sh/src/m16c/m16c_dumpstate.c
+++ b/nuttx/arch/sh/src/m16c/m16c_dumpstate.c
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <debug.h>
#include <nuttx/irq.h>
@@ -77,9 +77,9 @@
* Name: m16c_getsp
****************************************************************************/
-static inline uint16 m16c_getsp(void)
+static inline uint16_t) m16c_getsp(void)
{
- uint16 sp;
+ uint16_t) sp;
__asm__ __volatile__
(
@@ -96,10 +96,10 @@ static inline uint16 m16c_getsp(void)
****************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
-static inline uint16 m16c_getusersp(void)
+static inline uint16_t) m16c_getusersp(void)
{
- ubyte *ptr = (ubyte*) current_regs;
- return (uint16)ptr[REG_SP] << 8 | ptr[REG_SP+1];
+ uint8_t *ptr = (uint8_t*) current_regs;
+ return (uint16_t))ptr[REG_SP] << 8 | ptr[REG_SP+1];
}
#endif
@@ -107,13 +107,13 @@ static inline uint16 m16c_getusersp(void)
* Name: m16c_stackdump
****************************************************************************/
-static void m16c_stackdump(uint16 sp, uint16 stack_base)
+static void m16c_stackdump(uint16_t) sp, uint16_t) stack_base)
{
- uint16 stack;
+ uint16_t) stack;
for (stack = sp & ~7; stack < stack_base; stack += 8)
{
- ubyte *ptr = (ubyte*)stack;
+ uint8_t *ptr = (uint8_t*)stack;
lldbg("%04x: %02x %02x %02x %02x %02x %02x %02x %02x\n",
stack, ptr[0], ptr[1], ptr[2], ptr[3], ptr[4], ptr[5], ptr[6], ptr[7]);
}
@@ -125,7 +125,7 @@ static void m16c_stackdump(uint16 sp, uint16 stack_base)
static inline void m16c_registerdump(void)
{
- ubyte *ptr = (ubyte*) current_regs;
+ uint8_t *ptr = (uint8_t*) current_regs;
/* Are user registers available from interrupt processing? */
@@ -159,12 +159,12 @@ static inline void m16c_registerdump(void)
void up_dumpstate(void)
{
_TCB *rtcb = (_TCB*)g_readytorun.head;
- uint16 sp = m16c_getsp();
- uint16 ustackbase;
- uint16 ustacksize;
+ uint16_t) sp = m16c_getsp();
+ uint16_t) ustackbase;
+ uint16_t) ustacksize;
#if CONFIG_ARCH_INTERRUPTSTACK > 3
- uint16 istackbase;
- uint16 istacksize;
+ uint16_t) istackbase;
+ uint16_t) istacksize;
#endif
/* Get the limits on the user stack memory */
@@ -176,8 +176,8 @@ void up_dumpstate(void)
}
else
{
- ustackbase = (uint16)rtcb->adj_stack_ptr;
- ustacksize = (uint16)rtcb->adj_stack_size;
+ ustackbase = (uint16_t))rtcb->adj_stack_ptr;
+ ustacksize = (uint16_t))rtcb->adj_stack_size;
}
/* Get the limits on the interrupt stack memory. The near RAM memory map is as follows:
diff --git a/nuttx/arch/sh/src/m16c/m16c_initialstate.c b/nuttx/arch/sh/src/m16c/m16c_initialstate.c
index 189367279..deb6dd304 100644
--- a/nuttx/arch/sh/src/m16c/m16c_initialstate.c
+++ b/nuttx/arch/sh/src/m16c/m16c_initialstate.c
@@ -38,7 +38,8 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
+#include <stdint.h>
#include <string.h>
#include <nuttx/arch.h>
@@ -79,7 +80,7 @@
void up_initial_state(FAR _TCB *tcb)
{
FAR struct xcptcontext *xcp = &tcb->xcp;
- FAR ubyte *regs = xcp->regs;
+ FAR uint8_t *regs = xcp->regs;
/* Initialize the initial exception register context structure */
@@ -87,7 +88,7 @@ void up_initial_state(FAR _TCB *tcb)
/* Offset 0: FLG (bits 12-14) PC (bits 16-19) as would be present by an interrupt */
- *regs++ = ((M16C_DEFAULT_IPL << 4) | ((uint32)tcb->start >> 16));
+ *regs++ = ((M16C_DEFAULT_IPL << 4) | ((uint32_t)tcb->start >> 16));
/* Offset 1: FLG (bits 0-7) */
@@ -99,12 +100,12 @@ void up_initial_state(FAR _TCB *tcb)
/* Offset 2-3: 16-bit PC [0]:bits8-15 [1]:bits 0-7 */
- *regs++ = (uint32)tcb->start >> 8; /* Bits 8-15 of PC */
- *regs++ = (uint32)tcb->start; /* Bits 0-7 of PC */
+ *regs++ = (uint32_t)tcb->start >> 8; /* Bits 8-15 of PC */
+ *regs++ = (uint32_t)tcb->start; /* Bits 0-7 of PC */
/* Offset 18-20: User stack pointer */
regs = &xcp->regs[REG_SP];
- *regs++ = (uint32)tcb->adj_stack_ptr >> 8; /* Bits 8-15 of SP */
- *regs = (uint32)tcb->adj_stack_ptr; /* Bits 0-7 of SP */
+ *regs++ = (uint32_t)tcb->adj_stack_ptr >> 8; /* Bits 8-15 of SP */
+ *regs = (uint32_t)tcb->adj_stack_ptr; /* Bits 0-7 of SP */
}
diff --git a/nuttx/arch/sh/src/m16c/m16c_irq.c b/nuttx/arch/sh/src/m16c/m16c_irq.c
index beac525d4..10e129412 100644
--- a/nuttx/arch/sh/src/m16c/m16c_irq.c
+++ b/nuttx/arch/sh/src/m16c/m16c_irq.c
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
@@ -57,7 +57,7 @@
* structure. If is non-NULL only during interrupt processing.
*/
-uint32 *current_regs; /* Actually a pointer to the beginning or a ubyte array */
+uint32_t *current_regs; /* Actually a pointer to the beginning of a uint8_t array */
/****************************************************************************
* Private Data
diff --git a/nuttx/arch/sh/src/m16c/m16c_lowputc.c b/nuttx/arch/sh/src/m16c/m16c_lowputc.c
index 43f9b1946..b5d32d915 100644
--- a/nuttx/arch/sh/src/m16c/m16c_lowputc.c
+++ b/nuttx/arch/sh/src/m16c/m16c_lowputc.c
@@ -38,8 +38,8 @@
**************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <nuttx/arch.h>
#include "up_internal.h"
@@ -221,7 +221,7 @@ static inline int up_txready(void)
#if defined(HAVE_SERIALCONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
static inline void up_lowserialsetup(void)
{
- ubyte regval;
+ uint8_t regval;
/* Set the baud rate generator */
@@ -282,7 +282,7 @@ static inline void up_lowserialsetup(void)
/* Read any data left in the RX fifo */
- regval = (ubyte)getreg16(M16C_UART_BASE + M16C_UART_RB);
+ regval = (uint8_t)getreg16(M16C_UART_BASE + M16C_UART_RB);
}
#endif /* HAVE_SERIALCONFIG && !CONFIG_SUPPRESS_UART_CONFIG */
@@ -308,7 +308,7 @@ void up_lowputc(char ch)
/* Write the data to the transmit buffer */
- putreg16((uint16)ch, M16C_UART_BASE + M16C_UART_TB);
+ putreg16((uint16_t))ch, M16C_UART_BASE + M16C_UART_TB);
#endif
}
#endif
diff --git a/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c b/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
index c62399b6f..ae53e4ff5 100644
--- a/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
+++ b/nuttx/arch/sh/src/m16c/m16c_schedulesigaction.c
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
@@ -155,8 +155,8 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* disabled
*/
- current_regs[REG_PC] = (uint32)up_sigdeliver >> 8;
- current_regs[REG_PC+1] = (uint32)up_sigdeliver;
+ current_regs[REG_PC] = (uint32_t)up_sigdeliver >> 8;
+ current_regs[REG_PC+1] = (uint32_t)up_sigdeliver;
current_regs[REG_FLG] &= ~M16C_FLG_I;
/* And make sure that the saved context in the TCB
@@ -189,8 +189,8 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* disabled
*/
- tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver >> 8;
- tcb->xcp.regs[REG_PC+1] = (uint32)up_sigdeliver;
+ tcb->xcp.regs[REG_PC] = (uint32_t)up_sigdeliver >> 8;
+ tcb->xcp.regs[REG_PC+1] = (uint32_t)up_sigdeliver;
tcb->xcp.regs[REG_FLG] &= ~M16C_FLG_I;
}
diff --git a/nuttx/arch/sh/src/m16c/m16c_serial.c b/nuttx/arch/sh/src/m16c/m16c_serial.c
index cefbbbf9b..9f569ec16 100644
--- a/nuttx/arch/sh/src/m16c/m16c_serial.c
+++ b/nuttx/arch/sh/src/m16c/m16c_serial.c
@@ -38,12 +38,16 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
#include <unistd.h>
#include <semaphore.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
+
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/serial.h>
@@ -243,37 +247,37 @@ elif !defined(CONFIG_UART1_DISABLE)
struct up_dev_s
{
- uint32 baud; /* Configured baud */
- uint16 uartbase; /* Base address of UART registers */
- ubyte uartno; /* UART number */
- volatile ubyte ucon; /* Saved SCR value */
- volatile ubyte ssr; /* Saved SR value (only used during interrupt processing) */
- ubyte rcvirq; /* UART receive data available IRQ */
- ubyte xmtirq; /* UART transmit complete IRQ */
- ubyte enables; /* Bit 0: 1=RX enabled, Bit 1: 1=TX enabled */
- ubyte parity; /* 0=none, 1=odd, 2=even */
- ubyte bits; /* Number of bits (7 or 8) */
- boolean stopbits2; /* TRUE: Configure with 2 stop bits instead of 1 */
+ uint32_t baud; /* Configured baud */
+ uint16_t uartbase; /* Base address of UART registers */
+ uint8_t uartno; /* UART number */
+ volatile uint8_t ucon; /* Saved SCR value */
+ volatile uint8_t ssr; /* Saved SR value (only used during interrupt processing) */
+ uint8_t rcvirq; /* UART receive data available IRQ */
+ uint8_t xmtirq; /* UART transmit complete IRQ */
+ uint8_t enables; /* Bit 0: 1=RX enabled, Bit 1: 1=TX enabled */
+ uint8_t parity; /* 0=none, 1=odd, 2=even */
+ uint8_t bits; /* Number of bits (7 or 8) */
+ bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-static int up_setup(struct uart_dev_s *dev);
-static void up_shutdown(struct uart_dev_s *dev);
-static int up_attach(struct uart_dev_s *dev);
-static void up_detach(struct uart_dev_s *dev);
-static int up_rcvinterrupt(int irq, void *context);
-static int up_receive(struct uart_dev_s *dev, unsigned int *status);
-static void m16c_rxint(struct up_dev_s *dev, boolean enable);
-static void up_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean up_rxavailable(struct uart_dev_s *dev);
-static int up_xmtinterrupt(int irq, void *context);
-static void up_send(struct uart_dev_s *dev, int ch);
-static void m16c_txint(struct up_dev_s *dev, boolean enable);
-static void up_txint(struct uart_dev_s *dev, boolean enable);
-static boolean up_txready(struct uart_dev_s *dev);
+static int up_setup(struct uart_dev_s *dev);
+static void up_shutdown(struct uart_dev_s *dev);
+static int up_attach(struct uart_dev_s *dev);
+static void up_detach(struct uart_dev_s *dev);
+static int up_rcvinterrupt(int irq, void *context);
+static int up_receive(struct uart_dev_s *dev, unsigned int *status);
+static void m16c_rxint(struct up_dev_s *dev, bool enable);
+static void up_rxint(struct uart_dev_s *dev, bool enable);
+static bool up_rxavailable(struct uart_dev_s *dev);
+static int up_xmtinterrupt(int irq, void *context);
+static void up_send(struct uart_dev_s *dev, int ch);
+static void m16c_txint(struct up_dev_s *dev, bool enable);
+static void up_txint(struct uart_dev_s *dev, bool enable);
+static bool up_txready(struct uart_dev_s *dev);
/****************************************************************************
* Private Variables
@@ -413,7 +417,7 @@ static uart_dev_t g_uart2port =
* Name: up_serialin
****************************************************************************/
-static inline ubyte up_serialin(struct up_dev_s *priv, int offset)
+static inline uint8_t up_serialin(struct up_dev_s *priv, int offset)
{
return getreg8(priv->uartbase + offset);
}
@@ -422,7 +426,7 @@ static inline ubyte up_serialin(struct up_dev_s *priv, int offset)
* Name: up_serialin16
****************************************************************************/
-static inline uint16 up_serialin16(struct up_dev_s *priv, int offset)
+static inline uint16_t up_serialin16(struct up_dev_s *priv, int offset)
{
return getreg16(priv->uartbase + offset);
}
@@ -431,7 +435,7 @@ static inline uint16 up_serialin16(struct up_dev_s *priv, int offset)
* Name: up_serialout
****************************************************************************/
-static inline void up_serialout(struct up_dev_s *priv, int offset, ubyte value)
+static inline void up_serialout(struct up_dev_s *priv, int offset, uint8_t value)
{
putreg8(value, priv->uartbase + offset);
}
@@ -440,7 +444,7 @@ static inline void up_serialout(struct up_dev_s *priv, int offset, ubyte value)
* Name: up_serialout16
****************************************************************************/
-static inline void up_serialout16(struct up_dev_s *priv, int offset, uint16 value)
+static inline void up_serialout16(struct up_dev_s *priv, int offset, uint16_t value)
{
putreg16(value, priv->uartbase + offset);
}
@@ -449,11 +453,11 @@ static inline void up_serialout16(struct up_dev_s *priv, int offset, uint16 valu
* Name: up_disableuartint
****************************************************************************/
-static inline void up_disableuartint(struct up_dev_s *priv, ubyte *penables)
+static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *penables)
{
- ubyte enables = priv->enables;
- m16c_txint(priv, FALSE);
- m16c_rxint(priv, FALSE);
+ uint8_t enables = priv->enables;
+ m16c_txint(priv, false);
+ m16c_rxint(priv, false);
if (enables)
{
@@ -465,7 +469,7 @@ static inline void up_disableuartint(struct up_dev_s *priv, ubyte *penables)
* Name: up_restoreuartint
****************************************************************************/
-static inline void up_restoreuartint(struct up_dev_s *priv, ubyte enables)
+static inline void up_restoreuartint(struct up_dev_s *priv, uint8_t enables)
{
m16c_rxint(priv, (enables & M16C_RXENABLED) != 0);
m16c_txint(priv, (enables & M16C_TXENABLED) != 0);
@@ -506,7 +510,7 @@ static inline void up_waittxready(struct up_dev_s *priv)
static inline void ub_setbrg(struct up_dev_s *priv, unsigned int baud)
{
- uint16 brg;
+ uint16_t brg;
/* The Bit Rate Generator (BRG) value can be calculated by:
*
@@ -519,7 +523,7 @@ static inline void ub_setbrg(struct up_dev_s *priv, unsigned int baud)
* BRG = 20,000,000/1/16/19200 - 1 = 64
*/
- brg = (M16C_XIN_FREQ / (16L * M16C_XIN_PRESCALER * (uint32)baud)) - 1;
+ brg = (M16C_XIN_FREQ / (16L * M16C_XIN_PRESCALER * (uint32_t)baud)) - 1;
up_serialout(priv, M16C_UART_BRG, brg);
}
@@ -537,7 +541,7 @@ static int up_setup(struct uart_dev_s *dev)
{
#ifndef CONFIG_SUPPRESS_UART_CONFIG
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- ubyte regval;
+ uint8_t regval;
/* Set the baud rate generator */
@@ -549,8 +553,8 @@ static int up_setup(struct uart_dev_s *dev)
/* Disable RX/TX interrupts */
- m16c_rxint(priv, FALSE);
- m16c_txint(priv, FALSE);
+ m16c_rxint(priv, false);
+ m16c_txint(priv, false);
/* Set interrupt cause=TX complete and continuous receive mode */
@@ -664,7 +668,7 @@ static int up_setup(struct uart_dev_s *dev)
/* Read any data left in the RX fifo */
- regval = (ubyte)up_serialin16(priv, M16C_UART_RB);
+ regval = (uint8_t)up_serialin16(priv, M16C_UART_RB);
#endif
return OK;
}
@@ -806,7 +810,7 @@ static int up_rcvinterrupt(int irq, void *context)
static int up_receive(struct uart_dev_s *dev, unsigned int *status)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- uint16 rb;
+ uint16_t rb;
/* Read the character from the readbuffer */
@@ -829,11 +833,11 @@ static int up_receive(struct uart_dev_s *dev, unsigned int *status)
*
****************************************************************************/
-static void m16c_rxint(struct up_dev_s *dev, boolean enable)
+static void m16c_rxint(struct up_dev_s *dev, bool enable)
{
irqstate_t flags;
- uint16 regaddr;
- ubyte regvalue;
+ uint16_t)_t regaddr;
+ uint8_t regvalue;
/* Disable interrupts to prevent asynchronous accesses */
@@ -889,7 +893,7 @@ static void m16c_rxint(struct up_dev_s *dev, boolean enable)
irqrestore(flags);
}
-static void up_rxint(struct uart_dev_s *dev, boolean enable)
+static void up_rxint(struct uart_dev_s *dev, bool enable)
{
m16c_rxint((struct up_dev_s*)dev->priv, enable);
}
@@ -898,11 +902,11 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
* Name: up_rxavailable
*
* Description:
- * Return TRUE if the RDR is not empty
+ * Return true if the RDR is not empty
*
****************************************************************************/
-static boolean up_rxavailable(struct uart_dev_s *dev)
+static bool up_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
@@ -973,7 +977,7 @@ static void up_send(struct uart_dev_s *dev, int ch)
/* Write the data to the transmit buffer */
- up_serialout16(priv, M16C_UART_TB, (uint16)ch);
+ up_serialout16(priv, M16C_UART_TB, (uint16_t)ch);
}
/****************************************************************************
@@ -984,11 +988,11 @@ static void up_send(struct uart_dev_s *dev, int ch)
*
****************************************************************************/
-static void m16c_txint(struct up_dev_s *dev, boolean enable)
+static void m16c_txint(struct up_dev_s *dev, bool enable)
{
irqstate_t flags;
- uint16 regaddr;
- ubyte regvalue;
+ uint16_t)_t regaddr;
+ uint8_t regvalue;
/* Disable interrupts to prevent asynchronous accesses */
@@ -1044,7 +1048,7 @@ static void m16c_txint(struct up_dev_s *dev, boolean enable)
irqrestore(flags);
}
-static void up_txint(struct uart_dev_s *dev, boolean enable)
+static void up_txint(struct uart_dev_s *dev, bool enable)
{
m16c_txint((struct up_dev_s*)dev->priv, enable);
}
@@ -1053,11 +1057,11 @@ static void up_txint(struct uart_dev_s *dev, boolean enable)
* Name: up_txready
*
* Description:
- * Return TRUE if the TDR is empty
+ * Return true if the TDR is empty
*
****************************************************************************/
-static boolean up_txready(struct uart_dev_s *dev)
+static bool up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return ((up_serialin(priv, M16C_UART_C1) & UART_C1_TI) != 0);
@@ -1098,7 +1102,7 @@ void up_earlyconsoleinit(void)
/* Configuration whichever one is the console */
#ifdef HAVE_SERIALCONSOLE
- CONSOLE_DEV.isconsole = TRUE;
+ CONSOLE_DEV.isconsole = true;
up_setup(&CONSOLE_DEV);
#endif
}
@@ -1145,7 +1149,7 @@ int up_putc(int ch)
{
#ifdef HAVE_SERIALCONSOLE
struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
- ubyte ucon;
+ uint8_t ucon;
up_disableuartint(priv, &ucon);
@@ -1156,11 +1160,11 @@ int up_putc(int ch)
/* Add CR */
up_waittxready(priv);
- up_serialout16(priv, M16C_UART_TB, (uint16)'\r');
+ up_serialout16(priv, M16C_UART_TB, (uint16_t)'\r');
}
up_waittxready(priv);
- up_serialout16(priv, M16C_UART_TB, (uint16)ch);
+ up_serialout16(priv, M16C_UART_TB, (uint16_t)ch);
up_waittxready(priv);
up_restoreuartint(priv, ucon);
diff --git a/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c b/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
index 5505e2e48..4493c28b4 100644
--- a/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
+++ b/nuttx/arch/sh/src/m16c/m16c_sigdeliver.c
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
@@ -83,7 +83,7 @@ void up_sigdeliver(void)
{
#ifndef CONFIG_DISABLE_SIGNALS
_TCB *rtcb = (_TCB*)g_readytorun.head;
- ubyte regs[XCPTCONTEXT_SIZE];
+ uint8_t regs[XCPTCONTEXT_SIZE];
sig_deliver_t sigdeliver;
/* Save the errno. This must be preserved throughout the
diff --git a/nuttx/arch/sh/src/m16c/m16c_timer.h b/nuttx/arch/sh/src/m16c/m16c_timer.h
index ce8509e66..22cc31682 100644
--- a/nuttx/arch/sh/src/m16c/m16c_timer.h
+++ b/nuttx/arch/sh/src/m16c/m16c_timer.h
@@ -41,7 +41,6 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
/************************************************************************************
* Definitions
diff --git a/nuttx/arch/sh/src/m16c/m16c_timerisr.c b/nuttx/arch/sh/src/m16c/m16c_timerisr.c
index 3cc632719..4a7493cd6 100644
--- a/nuttx/arch/sh/src/m16c/m16c_timerisr.c
+++ b/nuttx/arch/sh/src/m16c/m16c_timerisr.c
@@ -38,7 +38,8 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
+#include <stdint.h>
#include <time.h>
#include <debug.h>
@@ -126,7 +127,7 @@
*
****************************************************************************/
-int up_timerisr(int irq, uint32 *regs)
+int up_timerisr(int irq, uint32_t *regs)
{
/* Process timer interrupt */
diff --git a/nuttx/arch/sh/src/m16c/m16c_uart.h b/nuttx/arch/sh/src/m16c/m16c_uart.h
index 8f9b1a005..38f41ac28 100644
--- a/nuttx/arch/sh/src/m16c/m16c_uart.h
+++ b/nuttx/arch/sh/src/m16c/m16c_uart.h
@@ -41,7 +41,6 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
/************************************************************************************
* Definitions
diff --git a/nuttx/arch/sh/src/m16c/m16c_vectors.S b/nuttx/arch/sh/src/m16c/m16c_vectors.S
index 17f47f560..a07b2ab01 100644
--- a/nuttx/arch/sh/src/m16c/m16c_vectors.S
+++ b/nuttx/arch/sh/src/m16c/m16c_vectors.S
@@ -389,7 +389,7 @@ _m16c_commonvector:
reit /* Return from interrupt */
/************************************************************************************
- * Name: int up_saveusercontext(uint32 *regs)
+ * Name: int up_saveusercontext(uint32_t *regs)
*
* Description:
* Save the context of the calling function at the point of the return from the
@@ -456,7 +456,7 @@ _m16c_contextsave:
.size _up_saveusercontext, .-_up_saveusercontext
/************************************************************************************
- * Name: void up_fullcontextrestore(uint32 *regs)
+ * Name: void up_fullcontextrestore(uint32_t *regs)
*
* Description:
* Restore the context of the using the provided register save array.
diff --git a/nuttx/arch/sh/src/sh1/chip.h b/nuttx/arch/sh/src/sh1/chip.h
index c10322a13..21204155f 100644
--- a/nuttx/arch/sh/src/sh1/chip.h
+++ b/nuttx/arch/sh/src/sh1/chip.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/sh/src/sh1/chip.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
@@ -41,7 +41,7 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#ifdef CONFIG_ARCH_SH7032
# include "sh1_703x.h"
@@ -63,7 +63,7 @@
#ifndef __ASSEMBLY__
# if CONFIG_ARCH_INTERRUPTSTACK > 3
- extern uint32 g_userstack;
+ extern uint32_t g_userstack;
# endif
#endif
diff --git a/nuttx/arch/sh/src/sh1/sh1_703x.h b/nuttx/arch/sh/src/sh1/sh1_703x.h
index 160afac96..b79bbb039 100644
--- a/nuttx/arch/sh/src/sh1/sh1_703x.h
+++ b/nuttx/arch/sh/src/sh1/sh1_703x.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/sh/src/sh1/sh1_703x.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
@@ -41,7 +41,6 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
/************************************************************************************
* Definitions
diff --git a/nuttx/arch/sh/src/sh1/sh1_copystate.c b/nuttx/arch/sh/src/sh1/sh1_copystate.c
index 4449c0425..3b0863eb7 100644
--- a/nuttx/arch/sh/src/sh1/sh1_copystate.c
+++ b/nuttx/arch/sh/src/sh1/sh1_copystate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/sh1/up_copystate.c
*
- * Copyright (C) 2008, 2009 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
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include "os_internal.h"
#include "up_internal.h"
@@ -66,7 +66,7 @@
/* A little faster than most memcpy's */
-void up_copystate(uint32 *dest, uint32 *src)
+void up_copystate(uint32_t *dest, uint32_t *src)
{
int i;
for (i = 0; i < XCPTCONTEXT_REGS; i++)
diff --git a/nuttx/arch/sh/src/sh1/sh1_dumpstate.c b/nuttx/arch/sh/src/sh1/sh1_dumpstate.c
index 55f998cca..cf6a16cbe 100755
--- a/nuttx/arch/sh/src/sh1/sh1_dumpstate.c
+++ b/nuttx/arch/sh/src/sh1/sh1_dumpstate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/sh1/sh1_assert.c
*
- * Copyright (C) 2008, 2009 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
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <debug.h>
#include <nuttx/irq.h>
@@ -76,9 +76,9 @@
* Name: sh1_getsp
****************************************************************************/
-static inline uint32 sh1_getsp(void)
+static inline uint32_t sh1_getsp(void)
{
- uint32 sp;
+ uint32_t sp;
__asm__ __volatile__
(
@@ -94,13 +94,13 @@ static inline uint32 sh1_getsp(void)
* Name: sh1_stackdump
****************************************************************************/
-static void sh1_stackdump(uint32 sp, uint32 stack_base)
+static void sh1_stackdump(uint32_t sp, uint32_t stack_base)
{
- uint32 stack ;
+ uint32_t stack ;
for (stack = sp & ~0x1f; stack < stack_base; stack += 32)
{
- uint32 *ptr = (uint32*)stack;
+ uint32_t *ptr = (uint32_t*)stack;
lldbg("%08x: %08x %08x %08x %08x %08x %08x %08x %08x\n",
stack, ptr[0], ptr[1], ptr[2], ptr[3],
ptr[4], ptr[5], ptr[6], ptr[7]);
@@ -113,7 +113,7 @@ static void sh1_stackdump(uint32 sp, uint32 stack_base)
static inline void sh1_registerdump(void)
{
- uint32 *ptr = current_regs;
+ uint32_t *ptr = current_regs;
/* Are user registers available from interrupt processing? */
@@ -147,13 +147,13 @@ static inline void sh1_registerdump(void)
void up_dumpstate(void)
{
- _TCB *rtcb = (_TCB*)g_readytorun.head;
- uint32 sp = sh1_getsp();
- uint32 ustackbase;
- uint32 ustacksize;
+ _TCB *rtcb = (_TCB*)g_readytorun.head;
+ uint32_t sp = sh1_getsp();
+ uint32_t ustackbase;
+ uint32_t ustacksize;
#if CONFIG_ARCH_INTERRUPTSTACK > 3
- uint32 istackbase;
- uint32 istacksize;
+ uint32_t istackbase;
+ uint32_t istacksize;
#endif
/* Get the limits on the user stack memory */
@@ -165,14 +165,14 @@ void up_dumpstate(void)
}
else
{
- ustackbase = (uint32)rtcb->adj_stack_ptr;
- ustacksize = (uint32)rtcb->adj_stack_size;
+ ustackbase = (uint32_t)rtcb->adj_stack_ptr;
+ ustacksize = (uint32_t)rtcb->adj_stack_size;
}
/* Get the limits on the interrupt stack memory */
#if CONFIG_ARCH_INTERRUPTSTACK > 3
- istackbase = (uint32)&g_userstack;
+ istackbase = (uint32_t)&g_userstack;
istacksize = (CONFIG_ARCH_INTERRUPTSTACK & ~3) - 4;
/* Show interrupt stack info */
diff --git a/nuttx/arch/sh/src/sh1/sh1_initialstate.c b/nuttx/arch/sh/src/sh1/sh1_initialstate.c
index 8ad4290e1..692561e86 100644
--- a/nuttx/arch/sh/src/sh1/sh1_initialstate.c
+++ b/nuttx/arch/sh/src/sh1/sh1_initialstate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/sh1/sh1_initialstate.c
*
- * Copyright (C) 2008, 2009 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
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <string.h>
#include <nuttx/arch.h>
#include "up_internal.h"
@@ -99,8 +99,8 @@ void up_initial_state(_TCB *tcb)
/* Initialize the initial exception register context structure */
memset(xcp, 0, sizeof(struct xcptcontext));
- xcp->regs[REG_SP] = (uint32)tcb->adj_stack_ptr;
- xcp->regs[REG_PC] = (uint32)tcb->start;
+ xcp->regs[REG_SP] = (uint32_t)tcb->adj_stack_ptr;
+ xcp->regs[REG_PC] = (uint32_t)tcb->start;
#ifdef CONFIG_SUPPRESS_INTERRUPTS
xcp->regs[REG_SR] = up_getsr() | 0x000000f0;
#else
diff --git a/nuttx/arch/sh/src/sh1/sh1_irq.c b/nuttx/arch/sh/src/sh1/sh1_irq.c
index 76c157f4f..c5b33cc3e 100644
--- a/nuttx/arch/sh/src/sh1/sh1_irq.c
+++ b/nuttx/arch/sh/src/sh1/sh1_irq.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/sh1/sh1_irq.c
*
- * 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
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <errno.h>
#include <debug.h>
@@ -57,7 +57,7 @@
* Public Data
****************************************************************************/
-uint32 *current_regs;
+uint32_t *current_regs;
/****************************************************************************
* Private Data
@@ -98,10 +98,10 @@ void up_irqinitialize(void)
void up_prioritize_irq(int irq, int priority)
{
- uint16 mask;
- uint16 reg16;
- uint32 reg;
- int shift;
+ uint16_t mask;
+ uint16_t reg16;
+ uint32_t reg;
+ int shift;
#ifdef CONFIG_DEBUG
if ((unsigned) irq > NR_IRQS || (unsigned)priority > 15)
diff --git a/nuttx/arch/sh/src/sh1/sh1_lowputc.c b/nuttx/arch/sh/src/sh1/sh1_lowputc.c
index 092093670..dd66c727b 100644
--- a/nuttx/arch/sh/src/sh1/sh1_lowputc.c
+++ b/nuttx/arch/sh/src/sh1/sh1_lowputc.c
@@ -1,7 +1,7 @@
/**************************************************************************
* arch/sh/src/sh1/sh1_lowputc.c
*
- * 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
@@ -38,8 +38,8 @@
**************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <nuttx/arch.h>
#include "up_internal.h"
@@ -197,7 +197,7 @@ static inline int up_txready(void)
void up_lowputc(char ch)
{
#ifdef HAVE_CONSOLE
- ubyte ssr;
+ uint8_t ssr;
/* Wait until the TDR is avaible */
@@ -228,7 +228,7 @@ void up_lowputc(char ch)
void up_lowsetup(void)
{
#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_SCI_CONFIG)
- ubyte scr;
+ uint8_t scr;
/* Disable the transmitter and receiver */
diff --git a/nuttx/arch/sh/src/sh1/sh1_schedulesigaction.c b/nuttx/arch/sh/src/sh1/sh1_schedulesigaction.c
index 3af182f37..6e7ba34e8 100644
--- a/nuttx/arch/sh/src/sh1/sh1_schedulesigaction.c
+++ b/nuttx/arch/sh/src/sh1/sh1_schedulesigaction.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/sh1/sh1_schedulesigaction.c
*
- * Copyright (C) 2008, 2009 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
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
@@ -154,7 +154,7 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* disabled
*/
- current_regs[REG_PC] = (uint32)up_sigdeliver;
+ current_regs[REG_PC] = (uint32_t)up_sigdeliver;
current_regs[REG_SR] |= 0x000000f0;
/* And make sure that the saved context in the TCB
@@ -186,7 +186,7 @@ void up_schedule_sigaction(_TCB *tcb, sig_deliver_t sigdeliver)
* disabled
*/
- tcb->xcp.regs[REG_PC] = (uint32)up_sigdeliver;
+ tcb->xcp.regs[REG_PC] = (uint32_t)up_sigdeliver;
tcb->xcp.regs[REG_SR] |= 0x000000f0 ;
}
diff --git a/nuttx/arch/sh/src/sh1/sh1_serial.c b/nuttx/arch/sh/src/sh1/sh1_serial.c
index 0be2bc280..69fda986a 100644
--- a/nuttx/arch/sh/src/sh1/sh1_serial.c
+++ b/nuttx/arch/sh/src/sh1/sh1_serial.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/sh1/sh1_serial.c
*
- * 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
@@ -38,12 +38,16 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
#include <unistd.h>
#include <semaphore.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
+
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/serial.h>
@@ -137,31 +141,31 @@
struct up_dev_s
{
- uint32 scibase; /* Base address of SCI registers */
- uint32 baud; /* Configured baud */
- volatile ubyte scr; /* Saved SCR value */
- volatile ubyte ssr; /* Saved SR value (only used during interrupt processing) */
- ubyte irq; /* Base IRQ associated with this SCI */
- ubyte parity; /* 0=none, 1=odd, 2=even */
- ubyte bits; /* Number of bits (7 or 8) */
- boolean stopbits2; /* TRUE: Configure with 2 stop bits instead of 1 */
+ uint32_t scibase; /* Base address of SCI registers */
+ uint32_t baud; /* Configured baud */
+ volatile uint8_t scr; /* Saved SCR value */
+ volatile uint8_t ssr; /* Saved SR value (only used during interrupt processing) */
+ uint8_t irq; /* Base IRQ associated with this SCI */
+ uint8_t parity; /* 0=none, 1=odd, 2=even */
+ uint8_t bits; /* Number of bits (7 or 8) */
+ bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-static int up_setup(struct uart_dev_s *dev);
-static void up_shutdown(struct uart_dev_s *dev);
-static int up_attach(struct uart_dev_s *dev);
-static void up_detach(struct uart_dev_s *dev);
-static int up_interrupt(int irq, void *context);
-static int up_receive(struct uart_dev_s *dev, uint32 *status);
-static void up_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean up_rxavailable(struct uart_dev_s *dev);
-static void up_send(struct uart_dev_s *dev, int ch);
-static void up_txint(struct uart_dev_s *dev, boolean enable);
-static boolean up_txready(struct uart_dev_s *dev);
+static int up_setup(struct uart_dev_s *dev);
+static void up_shutdown(struct uart_dev_s *dev);
+static int up_attach(struct uart_dev_s *dev);
+static void up_detach(struct uart_dev_s *dev);
+static int up_interrupt(int irq, void *context);
+static int up_receive(struct uart_dev_s *dev, uint32_t *status);
+static void up_rxint(struct uart_dev_s *dev, bool enable);
+static bool up_rxavailable(struct uart_dev_s *dev);
+static void up_send(struct uart_dev_s *dev, int ch);
+static void up_txint(struct uart_dev_s *dev, bool enable);
+static bool up_txready(struct uart_dev_s *dev);
/****************************************************************************
* Private Variables
@@ -261,7 +265,7 @@ static uart_dev_t g_sci1port =
* Name: up_serialin
****************************************************************************/
-static inline ubyte up_serialin(struct up_dev_s *priv, int offset)
+static inline uint8_t up_serialin(struct up_dev_s *priv, int offset)
{
return getreg8(priv->scibase + offset);
}
@@ -270,7 +274,7 @@ static inline ubyte up_serialin(struct up_dev_s *priv, int offset)
* Name: up_serialout
****************************************************************************/
-static inline void up_serialout(struct up_dev_s *priv, int offset, ubyte value)
+static inline void up_serialout(struct up_dev_s *priv, int offset, uint8_t value)
{
putreg8(value, priv->scibase + offset);
}
@@ -279,7 +283,7 @@ static inline void up_serialout(struct up_dev_s *priv, int offset, ubyte value)
* Name: up_disablesciint
****************************************************************************/
-static inline void up_disablesciint(struct up_dev_s *priv, ubyte *scr)
+static inline void up_disablesciint(struct up_dev_s *priv, uint8_t *scr)
{
/* Return a copy of the current scr settings */
@@ -298,7 +302,7 @@ static inline void up_disablesciint(struct up_dev_s *priv, ubyte *scr)
* Name: up_restoresciint
****************************************************************************/
-static inline void up_restoresciint(struct up_dev_s *priv, ubyte scr)
+static inline void up_restoresciint(struct up_dev_s *priv, uint8_t scr)
{
/* Set the interrupt bits in the scr value */
@@ -368,8 +372,8 @@ static inline void up_setbrr(struct up_dev_s *priv, unsigned int baud)
* = 32
*/
- uint32 brr = ((((SH1_CLOCK + 16) / 32) + (baud >> 1)) / baud) - 1;
- up_serialout(priv, SH1_SCI_BRR_OFFSET, (uint16)brr);
+ uint32_t brr = ((((SH1_CLOCK + 16) / 32) + (baud >> 1)) / baud) - 1;
+ up_serialout(priv, SH1_SCI_BRR_OFFSET, (uint16_t))brr);
}
/****************************************************************************
@@ -386,7 +390,7 @@ static int up_setup(struct uart_dev_s *dev)
{
#ifndef CONFIG_SUPPRESS_SCI_CONFIG
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- ubyte smr;
+ uint8_t smr;
/* Disable the transmitter and receiver */
@@ -651,8 +655,8 @@ static int up_interrupt(int irq, void *context)
static int up_receive(struct uart_dev_s *dev, unsigned int *status)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- ubyte rdr;
- ubyte ssr;
+ uint8_t rdr;
+ uint8_t ssr;
/* Read the character from the RDR port */
@@ -668,7 +672,7 @@ static int up_receive(struct uart_dev_s *dev, unsigned int *status)
/* For status, return the SSR at the time that the interrupt was received */
- *status = (uint32)priv->ssr << 8 | rdr;
+ *status = (uint32_t)priv->ssr << 8 | rdr;
/* Return the received character */
@@ -683,7 +687,7 @@ static int up_receive(struct uart_dev_s *dev, unsigned int *status)
*
****************************************************************************/
-static void up_rxint(struct uart_dev_s *dev, boolean enable)
+static void up_rxint(struct uart_dev_s *dev, bool enable)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
irqstate_t flags;
@@ -719,11 +723,11 @@ static void up_rxint(struct uart_dev_s *dev, boolean enable)
* Name: up_rxavailable
*
* Description:
- * Return TRUE if the RDR is not empty
+ * Return true if the RDR is not empty
*
****************************************************************************/
-static boolean up_rxavailable(struct uart_dev_s *dev)
+static bool up_rxavailable(struct uart_dev_s *dev)
{
/* Return true if the RDR full bit is set in the SSR */
@@ -742,11 +746,11 @@ static boolean up_rxavailable(struct uart_dev_s *dev)
static void up_send(struct uart_dev_s *dev, int ch)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- ubyte ssr;
+ uint8_t ssr;
/* Write the data to the TDR */
- up_serialout(priv, SH1_SCI_TDR_OFFSET, (ubyte)ch);
+ up_serialout(priv, SH1_SCI_TDR_OFFSET, (uint8_t)ch);
/* Clear the TDRE bit in the SSR */
@@ -763,7 +767,7 @@ static void up_send(struct uart_dev_s *dev, int ch)
*
****************************************************************************/
-static void up_txint(struct uart_dev_s *dev, boolean enable)
+static void up_txint(struct uart_dev_s *dev, bool enable)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
irqstate_t flags;
@@ -814,11 +818,11 @@ static void up_txint(struct uart_dev_s *dev, boolean enable)
* Name: up_txready
*
* Description:
- * Return TRUE if the TDR is empty
+ * Return true if the TDR is empty
*
****************************************************************************/
-static boolean up_txready(struct uart_dev_s *dev)
+static bool up_txready(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
return (up_serialin(priv, SH1_SCI_SSR_OFFSET) & SH1_SCISSR_TDRE) != 0;
@@ -856,7 +860,7 @@ void up_earlyconsoleinit(void)
/* Configuration whichever one is the console */
#ifdef HAVE_CONSOLE
- CONSOLE_DEV.isconsole = TRUE;
+ CONSOLE_DEV.isconsole = true;
up_setup(&CONSOLE_DEV);
#endif
}
@@ -900,7 +904,7 @@ int up_putc(int ch)
{
#ifdef HAVE_CONSOLE
struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
- ubyte scr;
+ uint8_t scr;
up_disablesciint(priv, &scr);
@@ -915,7 +919,7 @@ int up_putc(int ch)
}
up_waittxready(priv);
- up_serialout(priv, SH1_SCI_TDR_OFFSET, (ubyte)ch);
+ up_serialout(priv, SH1_SCI_TDR_OFFSET, (uint8_t)ch);
up_waittxready(priv);
up_restoresciint(priv, scr);
diff --git a/nuttx/arch/sh/src/sh1/sh1_sigdeliver.c b/nuttx/arch/sh/src/sh1/sh1_sigdeliver.c
index 91e9163ff..cddec6041 100644
--- a/nuttx/arch/sh/src/sh1/sh1_sigdeliver.c
+++ b/nuttx/arch/sh/src/sh1/sh1_sigdeliver.c
@@ -1,7 +1,7 @@
/****************************************************************************
* common/up_sigdeliver.c
*
- * 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
@@ -39,7 +39,7 @@
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include <sched.h>
#include <debug.h>
@@ -83,7 +83,7 @@ void up_sigdeliver(void)
{
#ifndef CONFIG_DISABLE_SIGNALS
_TCB *rtcb = (_TCB*)g_readytorun.head;
- uint32 regs[XCPTCONTEXT_REGS];
+ uint32_t regs[XCPTCONTEXT_REGS];
sig_deliver_t sigdeliver;
/* Save the errno. This must be preserved throughout the
diff --git a/nuttx/arch/sh/src/sh1/sh1_timerisr.c b/nuttx/arch/sh/src/sh1/sh1_timerisr.c
index f29c141eb..7072c4c64 100644
--- a/nuttx/arch/sh/src/sh1/sh1_timerisr.c
+++ b/nuttx/arch/sh/src/sh1/sh1_timerisr.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/sh/src/sh1/sh1_timerisr.c
*
- * 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
@@ -38,9 +38,11 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+
+#include <stdint.h>
#include <time.h>
#include <debug.h>
+
#include <nuttx/arch.h>
#include <arch/board/board.h>
@@ -131,9 +133,9 @@
*
****************************************************************************/
-int up_timerisr(int irq, uint32 *regs)
+int up_timerisr(int irq, uint32_t *regs)
{
- ubyte reg8;
+ uint8_t reg8;
/* Process timer interrupt */
@@ -159,7 +161,7 @@ int up_timerisr(int irq, uint32 *regs)
void up_timerinit(void)
{
- ubyte reg8;
+ uint8_t reg8;
/* Clear timer counter 0 */