summaryrefslogtreecommitdiff
path: root/nuttx/arch/sh/src/m16c
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-16 16:05:08 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-16 16:05:08 +0000
commitf8a2fb3042d58963a00fe808d18f84eec6a0be71 (patch)
tree9f122b32d69abfaf364eab636ef8cc5bd7b730a2 /nuttx/arch/sh/src/m16c
parentf66691d238faf4858c8c9f5c5a53f118a1e1ab8e (diff)
downloadpx4-nuttx-f8a2fb3042d58963a00fe808d18f84eec6a0be71.tar.gz
px4-nuttx-f8a2fb3042d58963a00fe808d18f84eec6a0be71.tar.bz2
px4-nuttx-f8a2fb3042d58963a00fe808d18f84eec6a0be71.zip
Changing NuttX fixed size type names to C99 standard names -- things will be broken for awhile
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2357 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/sh/src/m16c')
-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
13 files changed, 123 insertions, 117 deletions
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.