summaryrefslogtreecommitdiff
path: root/nuttx/arch/z80/src/ez80
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/z80/src/ez80')
-rw-r--r--nuttx/arch/z80/src/ez80/chip.h8
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_clock.c4
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_copystate.c3
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_emac.c266
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_i2c.c1863
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_initialstate.c6
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_io.asm6
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_irq.c3
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_lowuart.c14
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_registerdump.c3
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_schedulesigaction.c6
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_serial.c123
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_sigdeliver.c3
-rwxr-xr-xnuttx/arch/z80/src/ez80/ez80_spi.c54
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_timerisr.c16
-rw-r--r--nuttx/arch/z80/src/ez80/ez80f91_emac.h16
-rw-r--r--nuttx/arch/z80/src/ez80/ez80f91_i2c.h1
-rw-r--r--nuttx/arch/z80/src/ez80/ez80f91_spi.h7
-rw-r--r--nuttx/arch/z80/src/ez80/switch.h5
-rw-r--r--nuttx/arch/z80/src/ez80/up_mem.h8
20 files changed, 1217 insertions, 1198 deletions
diff --git a/nuttx/arch/z80/src/ez80/chip.h b/nuttx/arch/z80/src/ez80/chip.h
index ca5745f31..3402943ae 100644
--- a/nuttx/arch/z80/src/ez80/chip.h
+++ b/nuttx/arch/z80/src/ez80/chip.h
@@ -2,7 +2,7 @@
* arch/z80/src/ez80/chip.h
* arch/z80/src/chip/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,6 +41,10 @@
* Included Files
************************************************************************************/
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
/************************************************************************************
* Definitions
************************************************************************************/
@@ -78,7 +82,7 @@ extern "C" {
#define EXTERN extern
#endif
-EXTERN uint32 ez80_systemclock;
+EXTERN uint32_t ez80_systemclock;
/************************************************************************************
* Public Function Prototypes
diff --git a/nuttx/arch/z80/src/ez80/ez80_clock.c b/nuttx/arch/z80/src/ez80/ez80_clock.c
index 4f3134624..8446e8124 100644
--- a/nuttx/arch/z80/src/ez80/ez80_clock.c
+++ b/nuttx/arch/z80/src/ez80/ez80_clock.c
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
#include "arch/board/board.h"
@@ -54,7 +54,7 @@
* Private Data
****************************************************************************/
-uint32 ez80_systemclock = EZ80_SYS_CLK_FREQ;
+uint32_t ez80_systemclock = EZ80_SYS_CLK_FREQ;
/****************************************************************************
* Private Functions
diff --git a/nuttx/arch/z80/src/ez80/ez80_copystate.c b/nuttx/arch/z80/src/ez80/ez80_copystate.c
index 842457982..976817c6e 100644
--- a/nuttx/arch/z80/src/ez80/ez80_copystate.c
+++ b/nuttx/arch/z80/src/ez80/ez80_copystate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_copystate.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 <arch/irq.h>
#include "chip/switch.h"
diff --git a/nuttx/arch/z80/src/ez80/ez80_emac.c b/nuttx/arch/z80/src/ez80/ez80_emac.c
index bbfe74675..75b96a6be 100644
--- a/nuttx/arch/z80/src/ez80/ez80_emac.c
+++ b/nuttx/arch/z80/src/ez80/ez80_emac.c
@@ -43,6 +43,8 @@
#include <nuttx/config.h>
#if defined(CONFIG_NET) && defined(CONFIG_EZ80_EMAC)
+#include <stdint.h>
+#include <stdbool.h>
#include <time.h>
#include <string.h>
#include <debug.h>
@@ -242,21 +244,21 @@
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
struct ez80mac_statistics_s
{
- uint32 rx_int; /* Number of Rx interrupts received */
- uint32 rx_packets; /* Number of packets received (sum of the following): */
- uint32 rx_ip; /* Number of Rx IP packets received */
- uint32 rx_arp; /* Number of Rx ARP packets received */
- uint32 rx_dropped; /* Number of dropped, unsupported Rx packets */
- uint32 rx_nok; /* Number of Rx packets received without OK bit */
- uint32 rx_errors; /* Number of Rx errors (rx_overerrors + rx_nok) */
- uint32 rx_ovrerrors; /* Number of FIFO overrun errors */
- uint32 tx_int; /* Number of Tx interrupts received */
- uint32 tx_packets; /* Number of Tx descriptors queued */
- uint32 tx_errors; /* Number of Tx errors (sum of the following) */
- uint32 tx_abterrors; /* Number of aborted Tx descriptors */
- uint32 tx_fsmerrors; /* Number of Tx state machine errors */
- uint32 tx_timeouts; /* Number of Tx timeout errors */
- uint32 sys_int; /* Number of system interrupts received */
+ uint32_t rx_int; /* Number of Rx interrupts received */
+ uint32_t rx_packets; /* Number of packets received (sum of the following): */
+ uint32_t rx_ip; /* Number of Rx IP packets received */
+ uint32_t rx_arp; /* Number of Rx ARP packets received */
+ uint32_t rx_dropped; /* Number of dropped, unsupported Rx packets */
+ uint32_t rx_nok; /* Number of Rx packets received without OK bit */
+ uint32_t rx_errors; /* Number of Rx errors (rx_overerrors + rx_nok) */
+ uint32_t rx_ovrerrors; /* Number of FIFO overrun errors */
+ uint32_t tx_int; /* Number of Tx interrupts received */
+ uint32_t tx_packets; /* Number of Tx descriptors queued */
+ uint32_t tx_errors; /* Number of Tx errors (sum of the following) */
+ uint32_t tx_abterrors; /* Number of aborted Tx descriptors */
+ uint32_t tx_fsmerrors; /* Number of Tx state machine errors */
+ uint32_t tx_timeouts; /* Number of Tx timeout errors */
+ uint32_t sys_int; /* Number of system interrupts received */
};
# define _MKFIELD(a,b,c) a->b##c
# define EMAC_STAT(priv,name) _MKFIELD(priv,stat.,name)++
@@ -303,10 +305,10 @@ struct ez80emac_driver_s
FAR struct ez80emac_desc_s *rxnext;
FAR struct ez80emac_desc_s *rxendp1;
- boolean bifup; /* TRUE:ifup FALSE:ifdown */
- boolean blinkok; /* TRUE:successful MII autonegotiation */
- boolean bfullduplex; /* TRUE:full duplex */
- boolean b100mbs; /* TRUE:100Mbp */
+ bool bifup; /* true:ifup false:ifdown */
+ bool blinkok; /* true:successful MII autonegotiation */
+ bool bfullduplex; /* true:full duplex */
+ bool b100mbs; /* true:100Mbp */
WDOG_ID txpoll; /* TX poll timer */
WDOG_ID txtimeout; /* TX timeout timer */
@@ -336,49 +338,49 @@ static struct ez80emac_driver_s g_emac;
/* MII logic */
-static void ez80emac_waitmiibusy(void);
-static void ez80emac_miiwrite(FAR struct ez80emac_driver_s *priv, ubyte offset,
- uint16 value);
-static uint16 ez80emac_miiread(FAR struct ez80emac_driver_s *priv, uint32 offset);
-static boolean ez80emac_miipoll(FAR struct ez80emac_driver_s *priv, uint32 offset,
- uint16 bits, boolean bclear);
-static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv);
+static void ez80emac_waitmiibusy(void);
+static void ez80emac_miiwrite(FAR struct ez80emac_driver_s *priv, uint8_t offset,
+ uint16_t value);
+static uint16_t ez80emac_miiread(FAR struct ez80emac_driver_s *priv, uint32_t offset);
+static bool ez80emac_miipoll(FAR struct ez80emac_driver_s *priv, uint32_t offset,
+ uint16_t bits, bool bclear);
+static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv);
/* Multi-cast filtering */
#ifdef CONFIG_EZ80_MCFILTER
-static void ez80emac_machash(FAR ubyte *mac, int *ndx, int *bitno)
+static void ez80emac_machash(FAR uint8_t *mac, int *ndx, int *bitno)
#endif
/* TX/RX logic */
-static int ez80emac_transmit(struct ez80emac_driver_s *priv);
-static int ez80emac_uiptxpoll(struct uip_driver_s *dev);
+static int ez80emac_transmit(struct ez80emac_driver_s *priv);
+static int ez80emac_uiptxpoll(struct uip_driver_s *dev);
static inline FAR struct ez80emac_desc_s *ez80emac_rwp(void);
static inline FAR struct ez80emac_desc_s *ez80emac_rrp(void);
-static int ez80emac_receive(struct ez80emac_driver_s *priv);
+static int ez80emac_receive(struct ez80emac_driver_s *priv);
/* Interrupt handling */
-static int ez80emac_txinterrupt(int irq, FAR void *context);
-static int ez80emac_rxinterrupt(int irq, FAR void *context);
-static int ez80emac_sysinterrupt(int irq, FAR void *context);
+static int ez80emac_txinterrupt(int irq, FAR void *context);
+static int ez80emac_rxinterrupt(int irq, FAR void *context);
+static int ez80emac_sysinterrupt(int irq, FAR void *context);
/* Watchdog timer expirations */
-static void ez80emac_polltimer(int argc, uint32 arg, ...);
-static void ez80emac_txtimeout(int argc, uint32 arg, ...);
+static void ez80emac_polltimer(int argc, uint32_t arg, ...);
+static void ez80emac_txtimeout(int argc, uint32_t arg, ...);
/* NuttX callback functions */
-static int ez80emac_ifup(struct uip_driver_s *dev);
-static int ez80emac_ifdown(struct uip_driver_s *dev);
-static int ez80emac_txavail(struct uip_driver_s *dev);
+static int ez80emac_ifup(struct uip_driver_s *dev);
+static int ez80emac_ifdown(struct uip_driver_s *dev);
+static int ez80emac_txavail(struct uip_driver_s *dev);
/* Initialization */
-static int ez80_emacinitialize(void);
+static int ez80_emacinitialize(void);
/****************************************************************************
* Private Functions
@@ -421,9 +423,9 @@ static void ez80emac_waitmiibusy(void)
*
****************************************************************************/
-static void ez80emac_miiwrite(FAR struct ez80emac_driver_s *priv, ubyte offset, uint16 value)
+static void ez80emac_miiwrite(FAR struct ez80emac_driver_s *priv, uint8_t offset, uint16_t value)
{
- ubyte regval;
+ uint8_t regval;
/* Wait for any preceding MII management operation to complete */
@@ -461,9 +463,9 @@ static void ez80emac_miiwrite(FAR struct ez80emac_driver_s *priv, ubyte offset,
*
****************************************************************************/
-static uint16 ez80emac_miiread(FAR struct ez80emac_driver_s *priv, uint32 offset)
+static uint16_t ez80emac_miiread(FAR struct ez80emac_driver_s *priv, uint32_t offset)
{
- ubyte regval;
+ uint8_t regval;
/* Wait for any preceding MII management operation to complete */
@@ -483,7 +485,7 @@ static uint16 ez80emac_miiread(FAR struct ez80emac_driver_s *priv, uint32 offset
/* Wait for MII management operation to complete */
ez80emac_waitmiibusy();
- return ((uint16)inp(EZ80_EMAC_PRSD_H) << 8 | inp(EZ80_EMAC_PRSD_L));
+ return ((uint16_t)inp(EZ80_EMAC_PRSD_H) << 8 | inp(EZ80_EMAC_PRSD_L));
}
/****************************************************************************
@@ -497,18 +499,18 @@ static uint16 ez80emac_miiread(FAR struct ez80emac_driver_s *priv, uint32 offset
* priv - Reference to the driver state structure
* offset - Register offset in PMD
* bits - Selects set of bits to wait for
- * bclear - TRUE:Return true when all bits in 'bits' are 0
- * FALSE:Return true when one or more bits in 'bits' are 1
+ * bclear - true:Return true when all bits in 'bits' are 0
+ * false:Return true when one or more bits in 'bits' are 1
*
* Returned Value:
- * TRUE:Bit has requested polarity; FALSE: EMAC_MXPOLLLOOPS exceeded
+ * true:Bit has requested polarity; false: EMAC_MXPOLLLOOPS exceeded
*
****************************************************************************/
-static boolean ez80emac_miipoll(FAR struct ez80emac_driver_s *priv, uint32 offset,
- uint16 bits, boolean bclear)
+static bool ez80emac_miipoll(FAR struct ez80emac_driver_s *priv, uint32_t offset,
+ uint16_t bits, bool bclear)
{
- uint16 value;
+ uint16_t value;
int i;
for (i = 0; i < EMAC_MXPOLLLOOPS; i++)
@@ -518,18 +520,18 @@ static boolean ez80emac_miipoll(FAR struct ez80emac_driver_s *priv, uint32 offse
{
if ((value & bits) == 0)
{
- return TRUE;
+ return true;
}
}
else
{
if ((value & bits) != 0)
{
- return TRUE;
+ return true;
}
}
}
- return FALSE;
+ return false;
}
/****************************************************************************
@@ -542,19 +544,19 @@ static boolean ez80emac_miipoll(FAR struct ez80emac_driver_s *priv, uint32 offse
* priv - Reference to the driver state structure
* offset - Register offset in PMD
* bits - Selects set of bits to wait for
- * bclear - TRUE:Return true when all bits in 'bits' are 0
- * FALSE:Return true when one or more bits in 'bits' are 1
+ * bclear - true:Return true when all bits in 'bits' are 0
+ * false:Return true when one or more bits in 'bits' are 1
*
* Returned Value:
- * TRUE:Bit has requested polarity; FALSE: EMAC_MXPOLLLOOPS exceeded
+ * true:Bit has requested polarity; false: EMAC_MXPOLLLOOPS exceeded
*
****************************************************************************/
#ifdef CONFIG_EZ80_PHYAM79C874
static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
{
- uint16 phyval;
- boolean bauto;
+ uint16_t phyval;
+ bool bauto;
int ret = OK;
int i;
@@ -584,12 +586,12 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
if (phyval & MII_MSR_ANEGABLE)
{
phyval = MII_MCR_ANRESTART | MII_MCR_ANENABLE;
- bauto = TRUE;
+ bauto = true;
}
else
{
phyval = 0;
- bauto = FALSE;
+ bauto = false;
/* PADEN - EMAC pads all short frames by adding zeroes to the end of
* the data field. This bit is used in conjunction with ADPADN
@@ -701,10 +703,10 @@ dumpregs:
#else
static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
{
- uint16 advertise;
- uint16 lpa;
- uint16 mcr;
- ubyte regval;
+ uint16_t advertise;
+ uint16_t lpa;
+ uint16_t mcr;
+ uint8_t regval;
/* Start auto-negotiation */
@@ -715,28 +717,28 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
/* Wait for auto-negotiation to start */
- if (!ez80emac_miipoll(priv, MII_MCR, MII_MCR_ANRESTART, FALSE))
+ if (!ez80emac_miipoll(priv, MII_MCR, MII_MCR_ANRESTART, false))
{
ndbg("Autonegotiation didn't start.\n");
}
/* Wait for auto-negotiation to complete */
- if (!ez80emac_miipoll(priv, MII_MSR, MII_MSR_ANEGCOMPLETE, TRUE))
+ if (!ez80emac_miipoll(priv, MII_MSR, MII_MSR_ANEGCOMPLETE, true))
{
ndbg("Autonegotiation didn't complete.\n");
}
/* Wait link */
- if (!ez80emac_miipoll(priv, MII_MSR, MII_MSR_LINKSTATUS, TRUE))
+ if (!ez80emac_miipoll(priv, MII_MSR, MII_MSR_LINKSTATUS, true))
{
ndbg("Link is down!\n");
- priv->blinkok = FALSE;
+ priv->blinkok = false;
}
else
{
- priv->blinkok = TRUE;
+ priv->blinkok = true;
}
/* Read capable media type */
@@ -753,8 +755,8 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
regval = inp(EZ80_EMAC_CFG1);
regval |= EMAC_CFG1_FULLHD; /* Enable full duplex mode */
outp(EZ80_EMAC_CFG1, regval);
- priv->b100mbs = TRUE;
- priv->bfullduplex = TRUE;
+ priv->b100mbs = true;
+ priv->bfullduplex = true;
}
/* Check for 100BASETX half duplex */
@@ -765,8 +767,8 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
regval = inp(EZ80_EMAC_CFG1);
regval &= ~EMAC_CFG1_FULLHD; /* Disable full duplex mode */
outp(EZ80_EMAC_CFG1, regval);
- priv->b100mbs = TRUE;
- priv->bfullduplex = FALSE;
+ priv->b100mbs = true;
+ priv->bfullduplex = false;
}
/* Check for 10BASETX full duplex */
@@ -777,8 +779,8 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
regval = inp(EZ80_EMAC_CFG1);
regval |= EMAC_CFG1_FULLHD; /* Enable full duplex mode */
outp(EZ80_EMAC_CFG1, regval);
- priv->b100mbs = FALSE;
- priv->bfullduplex = TRUE;
+ priv->b100mbs = false;
+ priv->bfullduplex = true;
}
/* Check for 10BASETX half duplex */
@@ -789,8 +791,8 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
regval = inp(EZ80_EMAC_CFG1);
regval &= ~EMAC_CFG1_FULLHD; /* Disable full duplex mode */
outp(EZ80_EMAC_CFG1, regval);
- priv->b100mbs = FALSE;
- priv->bfullduplex = FALSE;
+ priv->b100mbs = false;
+ priv->bfullduplex = false;
}
else
{
@@ -798,8 +800,8 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
regval = inp(EZ80_EMAC_CFG1);
regval &= ~EMAC_CFG1_FULLHD; /* Disable full duplex mode */
outp(EZ80_EMAC_CFG1, regval);
- priv->b100mbs = FALSE;
- priv->bfullduplex = FALSE;
+ priv->b100mbs = false;
+ priv->bfullduplex = false;
}
/* Set MII control */
@@ -847,7 +849,7 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
* Parameters:
* priv - Reference to the driver state structure
* mac - The MAC address to add
- * enable - TRUE: Enable filtering on this address; FALSE: disable
+ * enable - true: Enable filtering on this address; false: disable
*
* Returned Value:
* None
@@ -855,10 +857,10 @@ static int ez80emac_miiconfigure(FAR struct ez80emac_driver_s *priv)
****************************************************************************/
#ifdef CONFIG_EZ80_MCFILTER
-static void ez80emac_machash(FAR ubyte *mac, int *ndx, int *bitno)
+static void ez80emac_machash(FAR uint8_t *mac, int *ndx, int *bitno)
{
- uint32 hash;
- uint32 crc32;
+ uint32_t hash;
+ uint32_t crc32;
int i;
int j;
@@ -867,7 +869,7 @@ static void ez80emac_machash(FAR ubyte *mac, int *ndx, int *bitno)
crc32 = 0xffffffff;
for (i = 0; i < 6; i++)
{
- crc32 ^= (uint32)mac[i] & 0x0f;
+ crc32 ^= (uint32_t)mac[i] & 0x0f;
for (j = 0; j < 4; j++)
{
if (crc32 & 1)
@@ -880,7 +882,7 @@ static void ez80emac_machash(FAR ubyte *mac, int *ndx, int *bitno)
}
}
- crc32 ^= (uint32)mac[i] >> 4;
+ crc32 ^= (uint32_t)mac[i] >> 4;
for (j = 0; j < 4; j++)
{
if (crc32 & 1)
@@ -936,11 +938,11 @@ static int ez80emac_transmit(struct ez80emac_driver_s *priv)
{
FAR struct ez80emac_desc_s *txdesc;
FAR struct ez80emac_desc_s *txnext;
- ubyte *psrc;
- ubyte *pdest;
- uint24 len;
+ uint8_t *psrc;
+ uint8_t *pdest;
+ uint24_t len;
irqstate_t flags;
- ubyte regval;
+ uint8_t regval;
/* Careful: This function can be called from outside of the interrupt
* handler and, therefore, may be suspended when debug output is generated!
@@ -969,14 +971,14 @@ static int ez80emac_transmit(struct ez80emac_driver_s *priv)
txdesc = priv->txnext;
len = EMAC_PKTBUF_ALIGN(priv->dev.d_len + SIZEOF_EMACSDESC);
- txnext = (FAR struct ez80emac_desc_s *)((ubyte*)txdesc + len);
+ txnext = (FAR struct ez80emac_desc_s *)((uint8_t*)txdesc + len);
/* Handle wraparound to the beginning of the TX region */
- if ((ubyte*)txnext + SIZEOF_EMACSDESC >= (ubyte*)priv->rxstart)
+ if ((uint8_t*)txnext + SIZEOF_EMACSDESC >= (uint8_t*)priv->rxstart)
{
txnext = (FAR struct ez80emac_desc_s *)
- ((ubyte*)priv->txstart + ((ubyte*)txnext - (ubyte*)priv->rxstart));
+ ((uint8_t*)priv->txstart + ((uint8_t*)txnext - (uint8_t*)priv->rxstart));
}
priv->txnext = txnext;
@@ -987,8 +989,8 @@ static int ez80emac_transmit(struct ez80emac_driver_s *priv)
/* Copy the data to the next packet in the Tx buffer (handling wraparound) */
psrc = priv->dev.d_buf;
- pdest = (ubyte*)txdesc + SIZEOF_EMACSDESC;
- len = (ubyte*)priv->rxstart - pdest;
+ pdest = (uint8_t*)txdesc + SIZEOF_EMACSDESC;
+ len = (uint8_t*)priv->rxstart - pdest;
if (len >= priv->dev.d_len)
{
/* The entire packet will fit into the EMAC SRAM without wrapping */
@@ -1014,7 +1016,7 @@ static int ez80emac_transmit(struct ez80emac_driver_s *priv)
* perform the transmission on its next polling cycle.
*/
- txdesc->np = (uint24)priv->txnext;
+ txdesc->np = (uint24_t)priv->txnext;
txdesc->pktsize = priv->dev.d_len;
txdesc->stat = EMAC_TXDESC_OWNER;
@@ -1033,7 +1035,7 @@ static int ez80emac_transmit(struct ez80emac_driver_s *priv)
/* Setup the TX timeout watchdog (perhaps restarting the timer) */
- (void)wd_start(priv->txtimeout, EMAC_TXTIMEOUT, ez80emac_txtimeout, 1, (uint32)priv);
+ (void)wd_start(priv->txtimeout, EMAC_TXTIMEOUT, ez80emac_txtimeout, 1, (uint32_t)priv);
return OK;
}
@@ -1102,7 +1104,7 @@ static int ez80emac_uiptxpoll(struct uip_driver_s *dev)
static inline FAR struct ez80emac_desc_s *ez80emac_rwp(void)
{
return (FAR struct ez80emac_desc_s *)
- (CONFIG_EZ80_RAMADDR + ((uint24)inp(EZ80_EMAC_RWP_H) << 8) + (uint24)inp(EZ80_EMAC_RWP_L));
+ (CONFIG_EZ80_RAMADDR + ((uint24_t)inp(EZ80_EMAC_RWP_H) << 8) + (uint24_t)inp(EZ80_EMAC_RWP_L));
}
/****************************************************************************
@@ -1122,7 +1124,7 @@ static inline FAR struct ez80emac_desc_s *ez80emac_rwp(void)
static inline FAR struct ez80emac_desc_s *ez80emac_rrp(void)
{
return (FAR struct ez80emac_desc_s *)
- (CONFIG_EZ80_RAMADDR + ((uint24)inp(EZ80_EMAC_RRP_H) << 8) + (uint24)inp(EZ80_EMAC_RRP_L));
+ (CONFIG_EZ80_RAMADDR + ((uint24_t)inp(EZ80_EMAC_RRP_H) << 8) + (uint24_t)inp(EZ80_EMAC_RRP_L));
}
/****************************************************************************
@@ -1148,8 +1150,8 @@ static int ez80emac_receive(struct ez80emac_driver_s *priv)
{
FAR struct ez80emac_desc_s *rxdesc = priv->rxnext;
FAR struct ez80emac_desc_s *rwp;
- ubyte *psrc;
- ubyte *pdest;
+ uint8_t *psrc;
+ uint8_t *pdest;
int pktlen;
int npackets;
@@ -1208,14 +1210,14 @@ static int ez80emac_receive(struct ez80emac_driver_s *priv)
/* Copy the data data from the hardware to priv->dev.d_buf */
- psrc = (FAR ubyte*)priv->rxnext + SIZEOF_EMACSDESC;
+ psrc = (FAR uint8_t*)priv->rxnext + SIZEOF_EMACSDESC;
pdest = priv->dev.d_buf;
/* Check for wraparound */
- if ((FAR ubyte*)(psrc + pktlen) > (FAR ubyte*)priv->rxendp1)
+ if ((FAR uint8_t*)(psrc + pktlen) > (FAR uint8_t*)priv->rxendp1)
{
- int nbytes = (int)((FAR ubyte*)priv->rxendp1 - (FAR ubyte*)psrc);
+ int nbytes = (int)((FAR uint8_t*)priv->rxendp1 - (FAR uint8_t*)psrc);
nvdbg("RX wraps after %d bytes\n", nbytes + SIZEOF_EMACSDESC);
memcpy(pdest, psrc, nbytes);
@@ -1249,8 +1251,8 @@ static int ez80emac_receive(struct ez80emac_driver_s *priv)
* and the RRP to determine how many packets remain in the Rx buffer.
*/
- outp(EZ80_EMAC_RRP_L, (ubyte)((uint24)rxdesc & 0xff));
- outp(EZ80_EMAC_RRP_H, (ubyte)(((uint24)rxdesc >> 8) & 0xff));
+ outp(EZ80_EMAC_RRP_L, (uint8_t)((uint24_t)rxdesc & 0xff));
+ outp(EZ80_EMAC_RRP_H, (uint8_t)(((uint24_t)rxdesc >> 8) & 0xff));
nvdbg("rxnext=%p {%06x, %u, %04x} rrp=%06x rwp=%06x blkslft=%02x\n",
rxdesc, rxdesc->np, rxdesc->pktsize, rxdesc->stat,
@@ -1328,8 +1330,8 @@ static int ez80emac_txinterrupt(int irq, FAR void *context)
{
FAR struct ez80emac_driver_s *priv = &g_emac;
FAR struct ez80emac_desc_s *txhead = priv->txhead;
- ubyte regval;
- ubyte istat;
+ uint8_t regval;
+ uint8_t istat;
/* EMAC Tx interrupts:
*
@@ -1432,7 +1434,7 @@ static int ez80emac_txinterrupt(int irq, FAR void *context)
static int ez80emac_rxinterrupt(int irq, FAR void *context)
{
FAR struct ez80emac_driver_s *priv = &g_emac;
- ubyte istat;
+ uint8_t istat;
/* EMAC Rx interrupts:
*
@@ -1477,8 +1479,8 @@ static int ez80emac_rxinterrupt(int irq, FAR void *context)
static int ez80emac_sysinterrupt(int irq, FAR void *context)
{
FAR struct ez80emac_driver_s *priv = &g_emac;
- ubyte events;
- ubyte istat;
+ uint8_t events;
+ uint8_t istat;
/* EMAC system interrupts :
*
@@ -1553,7 +1555,7 @@ static int ez80emac_sysinterrupt(int irq, FAR void *context)
*
****************************************************************************/
-static void ez80emac_txtimeout(int argc, uint32 arg, ...)
+static void ez80emac_txtimeout(int argc, uint32_t arg, ...)
{
FAR struct ez80emac_driver_s *priv = (FAR struct ez80emac_driver_s *)arg;
irqstate_t flags;
@@ -1592,7 +1594,7 @@ static void ez80emac_txtimeout(int argc, uint32 arg, ...)
*
****************************************************************************/
-static void ez80emac_polltimer(int argc, uint32 arg, ...)
+static void ez80emac_polltimer(int argc, uint32_t arg, ...)
{
struct ez80emac_driver_s *priv = (struct ez80emac_driver_s *)arg;
@@ -1625,7 +1627,7 @@ static void ez80emac_polltimer(int argc, uint32 arg, ...)
static int ez80emac_ifup(FAR struct uip_driver_s *dev)
{
FAR struct ez80emac_driver_s *priv = (FAR struct ez80emac_driver_s *)dev->d_private;
- ubyte regval;
+ uint8_t regval;
int ret;
ndbg("Bringing up: MAC %02x:%02x:%02x:%02x:%02x:%02x\n",
@@ -1688,11 +1690,11 @@ static int ez80emac_ifup(FAR struct uip_driver_s *dev)
/* Set and activate a timer process */
- (void)wd_start(priv->txpoll, EMAC_WDDELAY, ez80emac_polltimer, 1, (uint32)priv);
+ (void)wd_start(priv->txpoll, EMAC_WDDELAY, ez80emac_polltimer, 1, (uint32_t)priv);
/* Enable the Ethernet interrupts */
- priv->bifup = TRUE;
+ priv->bifup = true;
up_enable_irq(EZ80_EMACRX_IRQ);
up_enable_irq(EZ80_EMACTX_IRQ);
up_enable_irq(EZ80_EMACSYS_IRQ);
@@ -1721,7 +1723,7 @@ static int ez80emac_ifdown(struct uip_driver_s *dev)
{
struct ez80emac_driver_s *priv = (struct ez80emac_driver_s *)dev->d_private;
irqstate_t flags;
- ubyte regval;
+ uint8_t regval;
/* Disable the Ethernet interrupt */
@@ -1745,7 +1747,7 @@ static int ez80emac_ifdown(struct uip_driver_s *dev)
outp(EZ80_EMAC_PTMR, 0);
- priv->bifup = FALSE;
+ priv->bifup = false;
irqrestore(flags);
return OK;
}
@@ -1809,8 +1811,8 @@ static int ez80emac_txavail(struct uip_driver_s *dev)
static int ez80_emacinitialize(void)
{
struct ez80emac_driver_s *priv = &g_emac;
- uint24 addr;
- ubyte regval;
+ uint24_t addr;
+ uint8_t regval;
int ret;
/* Reset the EMAC hardware */
@@ -1838,8 +1840,8 @@ static int ez80_emacinitialize(void)
*/
addr = CONFIG_EZ80_RAMADDR;
- outp(EZ80_EMAC_TLBP_L, (ubyte)(addr & 0xff));
- outp(EZ80_EMAC_TLBP_H, (ubyte)((addr >> 8) & 0xff));
+ outp(EZ80_EMAC_TLBP_L, (uint8_t)(addr & 0xff));
+ outp(EZ80_EMAC_TLBP_H, (uint8_t)((addr >> 8) & 0xff));
priv->txstart = (FAR struct ez80emac_desc_s *)(addr);
priv->txnext = priv->txstart;
@@ -1860,8 +1862,8 @@ static int ez80_emacinitialize(void)
*/
addr += EMAC_TXBUFSIZE;
- outp(EZ80_EMAC_BP_L, (ubyte)(addr & 0xff));
- outp(EZ80_EMAC_BP_H, (ubyte)((addr >> 8) & 0xff));
+ outp(EZ80_EMAC_BP_L, (uint8_t)(addr & 0xff));
+ outp(EZ80_EMAC_BP_H, (uint8_t)((addr >> 8) & 0xff));
priv->rxstart = (FAR struct ez80emac_desc_s *)(addr);
priv->rxnext = priv->rxstart;
@@ -1887,8 +1889,8 @@ static int ez80_emacinitialize(void)
* is limited to a minimum of 32 bytes, the last five bits are always zero.
*/
- outp(EZ80_EMAC_RRP_L, (ubyte)(addr & 0xff));
- outp(EZ80_EMAC_RRP_H, (ubyte)((addr >> 8) & 0xff));
+ outp(EZ80_EMAC_RRP_L, (uint8_t)(addr & 0xff));
+ outp(EZ80_EMAC_RRP_H, (uint8_t)((addr >> 8) & 0xff));
nvdbg("rrp=%02x%02x rwp=%02x%02x\n",
inp(EZ80_EMAC_RRP_H), inp(EZ80_EMAC_RRP_L),
@@ -1899,8 +1901,8 @@ static int ez80_emacinitialize(void)
*/
addr += EMAC_RXBUFSIZE;
- outp(EZ80_EMAC_RHBP_L, (ubyte)(addr & 0xff));
- outp(EZ80_EMAC_RHBP_H, (ubyte)((addr >> 8) & 0xff));
+ outp(EZ80_EMAC_RHBP_L, (uint8_t)(addr & 0xff));
+ outp(EZ80_EMAC_RHBP_H, (uint8_t)((addr >> 8) & 0xff));
priv->rxendp1 = (FAR struct ez80emac_desc_s *)addr;
nvdbg("rxendp1=%p rhbp=%02x%02x\n",
@@ -1932,7 +1934,7 @@ static int ez80_emacinitialize(void)
up_udelay(500);
ez80emac_miiwrite(priv, MII_MCR, MII_MCR_RESET);
- if (!ez80emac_miipoll(priv, MII_MCR, MII_MCR_RESET, FALSE))
+ if (!ez80emac_miipoll(priv, MII_MCR, MII_MCR_RESET, false))
{
ndbg("PHY reset error.\n");
}
@@ -1987,7 +1989,7 @@ static int ez80_emacinitialize(void)
/* PHY reset */
ez80emac_miiwrite(priv, MII_MCR, MII_MCR_RESET);
- if (!ez80emac_miipoll(priv, MII_MCR, MII_MCR_RESET, FALSE))
+ if (!ez80emac_miipoll(priv, MII_MCR, MII_MCR_RESET, false))
{
ndbg("PHY reset error.\n");
ret = -EIO;
@@ -2095,7 +2097,7 @@ errout:
* Parameters:
* dev - Reference to the uIP driver state structure
* mac - The MAC address to add
- * enable - TRUE: Enable filtering on this address; FALSE: disable
+ * enable - true: Enable filtering on this address; false: disable
*
* Returned Value:
* OK on success; Negated errno on failure.
@@ -2103,10 +2105,10 @@ errout:
****************************************************************************/
#ifdef CONFIG_ARCH_MCFILTER
-int up_multicastfilter(FAR struct uip_driver_s *dev, FAR ubyte *mac, boolean enable)
+int up_multicastfilter(FAR struct uip_driver_s *dev, FAR uint8_t *mac, bool enable)
{
FAR struct ez80emac_driver_s *priv = (FAR struct ez80emac_driver_s *)dev->priv;
- ubyte regval;
+ uint8_t regval;
int ndx;
int bit;
int i;
diff --git a/nuttx/arch/z80/src/ez80/ez80_i2c.c b/nuttx/arch/z80/src/ez80/ez80_i2c.c
index a1ca6c297..d9defb0cf 100644
--- a/nuttx/arch/z80/src/ez80/ez80_i2c.c
+++ b/nuttx/arch/z80/src/ez80/ez80_i2c.c
@@ -1,931 +1,932 @@
-/****************************************************************************
- * arch/z80/src/ez80/ez80_i2c.c
- *
- * Copyright(C) 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES(INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-
-#include <sys/types.h>
-#include <stdlib.h>
-#include <semaphore.h>
-#include <errno.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/i2c.h>
-#include <arch/io.h>
-#include <arch/board/board.h>
-
-#include "ez80f91.h"
-#include "ez80f91_i2c.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-struct ez80_i2cdev_s
-{
- const struct i2c_ops_s *ops; /* I2C vtable */
- uint16 ccr; /* Clock control register value */
- uint16 addr; /* 7- or 10-bit address */
- ubyte addr10 : 1; /* 1=Address is 10-bit */
-};
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/* Misc. Helpers */
-
-static void i2c_setccr(uint16 ccr);
-static uint16 i2c_getccr(uint32 frequency);
-static ubyte i2c_waitiflg(void);
-static void i2c_clriflg(void);
-static void i2c_start(void);
-static void i2c_stop(void);
-static int i2c_sendaddr(struct ez80_i2cdev_s *priv, ubyte readbit);
-
-/* I2C methods */
-
-static uint32 i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32 frequency);
-static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits);
-static int i2c_write(FAR struct i2c_dev_s *dev, const ubyte *buffer, int buflen);
-static int i2c_read(FAR struct i2c_dev_s *dev, ubyte *buffer, int buflen);
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-/* This function is normally prototyped int the ZiLOG header file sio.h */
-
-extern uint32 get_freq(void);
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static ubyte g_currccr; /* Current setting of I2C CCR register */
-static boolean g_initialized; /* TRUE:I2C has been initialized */
-static sem_t g_i2csem; /* Serialize I2C transfers */
-
-const struct i2c_ops_s g_ops =
-{
- i2c_setfrequency,
- i2c_setaddress,
- i2c_write,
- i2c_read,
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-/****************************************************************************
- * Name: i2c_semtake/i2c_semgive
- *
- * Description:
- * Take/Give the I2C semaphore.
- *
- * Input Parameters:
- * None
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-static void i2c_semtake(void)
-{
- /* Take the I2C semaphore (perhaps waiting) */
-
- while (sem_wait(&g_i2csem) != 0)
- {
- /* The only case that an error should occr here is if
- * the wait was awakened by a signal.
- */
-
- ASSERT(errno == EINTR);
- }
-}
-
-#define i2c_semgive() sem_post(&g_i2csem)
-
-/****************************************************************************
- * Name: i2c_setccr
- *
- * Description:
- * Set the current BRG value for this transaction
- *
- * Input Parameters:
- * ccr - BRG to set
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-static void i2c_setccr(uint16 ccr)
-{
- if (g_currccr != ccr)
- {
- outp(EZ80_I2C_CCR, ccr);
- g_currccr = ccr;
- }
-}
-
-/****************************************************************************
- * Name: i2c_getccr
- *
- * Description:
- * Calculate the BRG value
- *
- * Input Parameters:
- * fscl - The I2C frequency requested
- *
- * Returned Value:
- * Returns the actual frequency selected
- *
- ****************************************************************************/
-
-static uint16 i2c_getccr(uint32 fscl)
-{
- uint32 fsamp;
- uint32 ftmp;
- ubyte n;
- ubyte m;
-
- /* The sampling frequency is given by:
- *
- * fsamp = sysclock / 2**N
- *
- * And the I2C clock is determined by:
- *
- * fscl = sysclock / 10 / (M + 1) / 2**N
- * = fsamp / 10 / (M + 1)
- *
- * The fsmp must be >= 10 * fscl. The best solution is the smallest value of
- * N so that the sampling rate is the highest subject to:
- *
- * The minimum value of the fsamp is given by:
- */
-
- fsamp = 10 * fscl;
-
- /* Now, serarch for the smallest value of N that results in the actual
- * fsamp >= the ideal fsamp. Fortunately, we only have to check at most
- * eight values.
- */
-
- if (fsamp >= EZ80_SYS_CLK_FREQ)
- {
- ftmp = EZ80_SYS_CLK_FREQ / 10;
- n = 0;
- }
- else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 1))
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 1) / 10;
- n = 1;
- }
- else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 2))
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 2) / 10;
- n = 2;
- }
- else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 3))
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 3) / 10;
- n = 3;
- }
- else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 4))
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 4) / 10;
- n = 4;
- }
- else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 5))
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 5) / 10;
- n = 5;
- }
- else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 6))
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 6) / 10;
- n = 6;
- }
- else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 7))
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 7) / 10;
- n = 7;
- }
- else
- {
- ftmp = (EZ80_SYS_CLK_FREQ >> 7) / 10;
- fscl = ftmp;
- n = 7;
- }
-
- /* Finally, get M:
- *
- * M = (fsamp / 10) / fscl - 1 = ftmp / fscl - 1
- */
-
- m = ftmp / fscl;
- if (m > 0)
- {
- if (--m > 15)
- {
- m = 15;
- }
- }
-
- /* Return the value for CCR */
-
- return (n << I2C_CCR_NSHIFT) | (m << I2C_CCR_MSHIFT);
-}
-
-/****************************************************************************
- * Name: i2c_waitiflg
- *
- * Description:
- * In polled mode, we have to spin until the IFLG bit in the xxx register
- * goes to 1, signalling that the last send or receive is complete. This
- * could be used to generate an interrupt for a non-polled driver.
- *
- * Input Parameters:
- * priv - Device-specific state data
- * readbit - 0 or I2C_READBIT
- *
- * Returned Value:
- * The contents of the I2C_SR register at the time that IFLG became 1.
- *
- ****************************************************************************/
-
-static ubyte i2c_waitiflg(void)
-{
- while ((inp(EZ80_I2C_CTL) & I2C_CTL_IFLG) != 0);
- return inp(EZ80_I2C_SR);
-}
-
-/****************************************************************************
- * Name: i2c_clriflg
- *
- * Description:
- * Clear the IFLAG bit in the I2C_CTL register, acknowledging the event.
- * If interrupts are enabled, this would clear the interrupt status.
- *
- * Input Parameters:
- * None
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-static void i2c_clriflg(void)
-{
- ubyte regval = inp(EZ80_I2C_CTL);
- regval &= ~I2C_CTL_IFLG;
- outp(EZ80_I2C_CTL, regval);
-}
-
-/****************************************************************************
- * Name: i2c_start
- *
- * Description:
- * Send the START bit. IFLAG must be zero; it will go to 1 when it is
- * time to send the address.
- *
- * Input Parameters:
- * None
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-static void i2c_start(void)
-{
- ubyte regval = inp(EZ80_I2C_CTL);
- regval |= I2C_CTL_STA;
- outp(EZ80_I2C_CTL, regval);
-}
-
-/****************************************************************************
- * Name: i2c_stop
- *
- * Description:
- * Send the STOP bit. This terminates the I2C transfer and reverts back
- * to IDLE mode.
- *
- * Input Parameters:
- * None
- *
- * Returned Value:
- * None
- *
- ****************************************************************************/
-
-static void i2c_stop(void)
-{
- ubyte regval = inp(EZ80_I2C_CTL);
- regval |= I2C_CTL_STP;
- outp(EZ80_I2C_CTL, regval);
-}
-
-/****************************************************************************
- * Name: i2c_sendaddr
- *
- * Description:
- * Send the 8- or 11-bit address for either a read or a write transaction.
- *
- * Input Parameters:
- * priv - Device-specific state data
- * readbit - 0 or I2C_READBIT
- *
- * Returned Value:
- * 0: Success, IFLG is set and DATA can be sent or received.
-
- * Or <0: Negated error value. IFLG is cleared.
- *
- * -EIO: Irrecoverable (or unexpected) error occured
- * -EAGAIN: And
- *
- ****************************************************************************/
-
-static int i2c_sendaddr(struct ez80_i2cdev_s *priv, ubyte readbit)
-{
- ubyte sr;
- int ret = OK;
-
- /* Wait for the IFLG bit to transition to 1. At this point, we should
- * have status == 8 meaning that the start bit was sent successfully.
- */
-
- sr = i2c_waitiflg();
-#ifdef CONFIG_DEBUG
- if (sr != I2C_SR_MSTART)
- {
- /* This error should never occur */
-
- dbg("Bad START status: %02x\n", sr);
- i2c_clriflg();
- return -EIO;
- }
-#endif
-
- /* Now send the address */
-
- if (!priv->addr10)
- {
- /* Load the I2C_DR with the 8-bit I2C slave address and clear the
- * IFLG. Clearing the IFLAG will cause the address to be transferred.
- */
-
- outp(EZ80_I2C_DR, (ubyte)I2C_ADDR8(priv->addr) | readbit);
- i2c_clriflg();
-
- /* And wait for the address transfer to complete */
-
- sr = i2c_waitiflg();
- if (sr != I2C_SR_MADDRWRACK && sr != I2C_SR_MADDRWR)
- {
- dbg("Bad ADDR8 status: %02x\n", sr);
- goto failure;
- }
- }
- else
- {
- /* Load the I2C_DR with upper part of the 10->16-bit I2C slave address
- * and clear the IFLG. Clearing the IFLAG will cause the address to
- * be transferred.
- */
-
- outp(EZ80_I2C_DR, (ubyte)I2C_ADDR10H(priv->addr) | readbit);
- i2c_clriflg();
-
- /* And wait for the address transfer to complete */
-
- sr = i2c_waitiflg();
- if (sr != I2C_SR_MADDRWRACK && sr != I2C_SR_MADDRWR)
- {
- dbg("Bad ADDR10H status: %02x\n", sr);
- goto failure;
- }
-
- /* Now send the lower 8 bits of the 10-bit address */
-
- outp(EZ80_I2C_DR, (ubyte)I2C_ADDR10L(priv->addr));
- i2c_clriflg();
-
- /* And wait for the address transfer to complete */
-
- sr = i2c_waitiflg();
- if (sr != I2C_SR_MADDR2WRACK && sr != I2C_SR_MADDR2WR)
- {
- dbg("Bad ADDR10L status: %02x\n", sr);
- goto failure;
- }
- }
-
- return OK;
-
- /* We don't attempt any fancy status-based error recovery */
-
-failure:
-#ifdef CONFIG_DEBUG
- switch (sr)
- {
- case I2C_SR_ARBLOST1: /* Arbitration lost in address or data byte */
- case I2C_SR_ARBLOST2: /* Arbitration lost in address as master, slave address and Write bit received, ACK transmitted */
- case I2C_SR_ARBLOST3: /* Arbitration lost in address as master, General Call address received, ACK transmitted */
- case I2C_SR_ARBLOST4: /* Arbitration lost in address as master, slave address and Read bit received, ACK transmitted */
- dbg("Arbitration lost: %02x\n", sr);
- i2c_clriflg();
- return -EAGAIN;
-
- default:
- dbg("Unexpected status: %02x\n", sr);
- i2c_clriflg();
- return -EIO;
- }
-#else
- i2c_clriflg();
- return -EAGAIN;
-#endif
-}
-
-/****************************************************************************
- * Name: i2c_setfrequency
- *
- * Description:
- * Set the I2C frequency. This frequency will be retained in the struct
- * i2c_dev_s instance and will be used with all transfers. Required.
- *
- * Input Parameters:
- * dev - Device-specific state data
- * frequency - The I2C frequency requested
- *
- * Returned Value:
- * Returns the actual frequency selected
- *
- ****************************************************************************/
-
-static uint32 i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32 frequency)
-{
- FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
-
- /* Sanity Check */
-
-#ifdef CONFIG_DEBUG
- if (!dev)
- {
- dbg("Invalid inputs\n");
- return -EINVAL;
- }
-#endif
-
- /* Calculate and save the BRG (we won't apply it until the first transfer) */
-
- priv->ccr = i2c_getccr(frequency);
- return OK;
-}
-
-/****************************************************************************
- * Name: i2c_setaddress
- *
- * Description:
- * Set the I2C slave address. This frequency will be retained in the struct
- * i2c_dev_s instance and will be used with all transfers. Required.
- *
- * Input Parameters:
- * dev - Device-specific state data
- * address - The I2C slave address
- * nbits - The number of address bits provided (7 or 10)
- *
- * Returned Value:
- * Returns the actual frequency selected
- *
- ****************************************************************************/
-
-static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits)
-{
- FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
-
- /* Sanity Check */
-
-#ifdef CONFIG_DEBUG
- if (!dev || (unsigned)addr > 0x7f || (nbits != 7 && nbits != 10))
- {
- dbg("Invalid inputs\n");
- return -EINVAL;
- }
-#endif
-
- /* Save the 7- or 10-bit address */
-
- priv->addr = addr;
- priv->addr10 = (nbits == 10);
- return OK;
-}
-
-/****************************************************************************
- * Name: i2c_write
- *
- * Description:
- * Send a block of data on I2C using the previously selected I2C
- * frequency and slave address. Each write operational will be an 'atomic'
- * operation in the sense that any other I2C actions will be serialized
- * and pend until this write completes. Required.
- *
- * Input Parameters:
- * dev - Device-specific state data
- * buffer - A pointer to the read-only buffer of data to be written to device
- * buflen - The number of bytes to send from the buffer
- *
- * Returned Value:
- * 0: success, <0: A negated errno
- *
- ****************************************************************************/
-
-static int i2c_write(FAR struct i2c_dev_s *dev, const ubyte *buffer, int buflen)
-{
- FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
- const ubyte *ptr;
- ubyte sr;
- int retry;
- int count;
- int ret;
-
-#ifdef CONFIG_DEBUG
- if (!priv || !buffer || buflen < 1)
- {
- dbg("Invalid inputs\n");
- return -EINVAL;
- }
-#endif
-
- /* Get exclusive access */
-
- i2c_semtake();
-
- /* Set the frequency */
-
- i2c_setccr(priv->ccr);
-
- /* Retry as necessary to send this whole message */
-
- for (retry = 0; retry < 100; retry++)
- {
- /* Enter MASTER TRANSMIT mode by setting the STA bit in the I2C_CTL
- * register to 1. The I2C then tests the I2C bus and transmits a START
- * condition when the bus is free.
- */
-
- i2c_start();
-
- /* When a START condition is transmitted, the IFLG bit is 1. Then we may
- * send the I2C slave address.
- */
-
- ret = i2c_sendaddr(priv, 0);
- if (ret < 0)
- {
- if (ret == -EAGAIN)
- {
- continue;
- }
- else
- {
- goto failure;
- }
- }
-
- /* Then send all of the bytes in the buffer */
-
- ptr = buffer;
- for (count = buflen; count; count--)
- {
- /* Load the I2C_DR with next data byte and clear the IFLG. Clearing
- * the IFLAG will cause the data to be transferred.
- */
-
- outp(EZ80_I2C_DR, *ptr++);
- i2c_clriflg();
-
- /* And wait for the data transfer to complete */
-
- sr = i2c_waitiflg();
- if (sr != I2C_SR_MDATAWRACK && sr != I2C_SR_MDATAWR)
- {
- dbg("Bad DATA status: %02x\n", sr);
- i2c_clriflg();
- if (sr == I2C_SR_ARBLOST1)
- {
- /* Arbitration lost, break out of the inner loop and
- * try sending the message again
- */
-
- break;
- }
-
- /* Otherwise, it is fatal (shouldn't happen) */
-
- ret = -EIO;
- goto failure;
- }
-
- /* Data byte was sent successfully. Was that the last byte? */
-
- else if (count <= 1)
- {
- /* When all bytes are transmitted, the microcontroller must
- * write a 1 to the STP bit in the I2C_CTL register. The
- * I2C then transmits a STOP condition, clears the STP bit
- * and returns to an idle state.
- */
-
- i2c_stop();
-
- ret = OK;
- goto success;
- }
- }
- }
-
- /* If we get here, we timed out without successfully sending the message */
-
- ret = -ETIMEDOUT;
-
-success:
-failure:
- i2c_semgive();
- return ret;
-}
-
-/****************************************************************************
- * Name: i2c_read
- *
- * Description:
- * Receive a block of data from I2C using the previously selected I2C
- * frequency and slave address. Each read operational will be an 'atomic'
- * operation in the sense that any other I2C actions will be serialized
- * and pend until this read completes. Required.
- *
- * Input Parameters:
- * dev - Device-specific state data
- * buffer - A pointer to a buffer of data to receive the data from the device
- * buflen - The requested number of bytes to be read
- *
- * Returned Value:
- * 0: success, <0: A negated errno
- *
- ****************************************************************************/
-
-static int i2c_read(FAR struct i2c_dev_s *dev, ubyte *buffer, int buflen)
-{
- FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
- ubyte *ptr;
- ubyte regval;
- int retry;
- int count;
- int ret;
-
-#ifdef CONFIG_DEBUG
- if (!priv || !buffer || buflen < 1)
- {
- dbg("Invalid inputs\n");
- return -EINVAL;
- }
-#endif
-
- /* Get exclusive access */
-
- i2c_semtake();
-
- /* Set the frequency */
-
- i2c_setccr(priv->ccr);
-
- /* Retry as necessary to receive the whole message */
-
- for (retry = 0; retry < 100; retry++)
- {
- /* Enter MASTER TRANSMIT mode by setting the STA bit in the I2C_CTL
- * register to 1. The I2C then tests the I2C bus and transmits a START
- * condition when the bus is free.
- */
-
- i2c_start();
-
- /* When a START condition is transmitted, the IFLG bit is 1. Then we may
- * send the I2C slave address.
- */
-
- ret = i2c_sendaddr(priv, 0);
- if (ret < 0)
- {
- if (ret == -EAGAIN)
- {
- continue;
- }
- else
- {
- goto failure;
- }
- }
-
- /* Now loop to receive each data byte */
-
- ptr = buffer;
- for (count = buflen; count; count--)
- {
- /* Is this the last byte? If so, we must NACK it */
-
- regval = inp(EZ80_I2C_CTL);
- if (count <= 1)
- {
- /* If the AAK bit is cleared to 0 during a transfer, the I2C
- * transmits a NACK bit after the next byte is received.
- */
-
- regval &= ~I2C_CTL_AAK;
- }
- else
- {
- /* If the AAK bit in the I2C_CTL register is set to 1 then an
- * ACK bit is transmitted and the IFLG bit is set after each
- * byte is received.
- */
-
- regval |= I2C_CTL_AAK;
- }
- outp(EZ80_I2C_CTL, regval);
-
- /* Wait for IFLG to be set meaning that incoming data is
- * available in the I2C_DR registers.
- */
-
- regval = i2c_waitiflg();
-
- /* Data byte received in MASTER mode, ACK transmitted */
-
- if (regval == I2C_SR_MDATARDACK)
- {
- /* Since we just ACKed the incoming byte, it must NOT be the last */
-
- DEBUGASSERT(count > 1);
-
- /* Receive the data and clear the IFLGS */
-
- *ptr++ = inp(EZ80_I2C_DR);
- i2c_clriflg();
- }
-
- /* Data byte received in MASTER mode, NACK transmitted */
-
- else if (regval == I2C_SR_MDATARDNAK)
- {
- /* Since we just NACKed the incoming byte, it must be the last */
-
- DEBUGASSERT(count <= 1);
-
- /* When all bytes are received and the NACK has been sent, then the
- * microcontroller must write 1 to the STP bit in the I2C_CTL
- * register. The I2C then transmits a STOP condition, clears
- * the STP bit and returns to an idle state.
- */
-
- i2c_stop();
- i2c_clriflg();
-
- ret = OK;
- goto success;
- }
-
- /* Arbitration lost in address or data byte */
-
- else if (regval == I2C_SR_ARBLOST1)
- {
- /* Clear the IFLG and break out of the inner loop.
- * this will cause the whole transfer to start over
- */
-
- dbg("Arbitration lost: %02x\n", regval);
- i2c_clriflg();
- break;
- }
-
- /* Unexpected status response */
-
- else
- {
- dbg("Unexpected status: %02x\n", regval);
- i2c_clriflg();
- ret = -EIO;
- goto failure;
- }
- }
- }
- ret = -ETIMEDOUT;
-
-success:
-failure:
- i2c_semgive();
- return ret;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_i2cinitialize
- *
- * Description:
- * Initialize the selected I2C port. And return a unique instance of struct
- * struct i2c_dev_s. This function may be called to obtain multiple
- * instances of the interface, each of which may be set up with a
- * different frequency and slave address.
- *
- * Input Parameter:
- * Port number (for hardware that has mutiple I2C interfaces)
- *
- * Returned Value:
- * Valid I2C device structre reference on succcess; a NULL on failure
- *
- ****************************************************************************/
-
-FAR struct i2c_dev_s *up_i2cinitialize(int port)
-{
- FAR struct ez80_i2cdev_s *i2c;
- uint16 ccr;
- ubyte regval;
-
- if (!g_initialized)
- {
- /* Set up some initial BRG value */
-
- ccr = i2c_getccr(100*1000);
- i2c_setccr(ccr);
-
- /* No GPIO setup is required -- I2C pints, SCL/SDA are not multiplexed */
-
- /* This semaphore enforces serialized access for I2C transfers */
-
- sem_init(&g_i2csem, 0, 1);
-
- /* Enable I2C -- but not interrupts */
-
- regval = inp(EZ80_I2C_CTL);
- regval |= I2C_CTL_ENAB;
- outp(EZ80_I2C_CTL, regval);
- }
-
- /* Now, allocate an I2C instance for this caller */
-
- i2c = (FAR struct ez80_i2cdev_s *)malloc(sizeof(FAR struct ez80_i2cdev_s));
- if (i2c)
- {
- /* Initialize the allocated instance */
-
- i2c->ops = &g_ops;
- i2c->ccr = g_currccr;
- }
- return (FAR struct i2c_dev_s *)i2c;
-}
+/****************************************************************************
+ * arch/z80/src/ez80/ez80_i2c.c
+ *
+ * Copyright(C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES(INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/i2c.h>
+#include <arch/io.h>
+#include <arch/board/board.h>
+
+#include "ez80f91.h"
+#include "ez80f91_i2c.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct ez80_i2cdev_s
+{
+ const struct i2c_ops_s *ops; /* I2C vtable */
+ uint16_t ccr; /* Clock control register value */
+ uint16_t addr; /* 7- or 10-bit address */
+ uint8_t addr10 : 1; /* 1=Address is 10-bit */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* Misc. Helpers */
+
+static void i2c_setccr(uint16_t ccr);
+static uint16_t i2c_getccr(uint32_t frequency);
+static uint8_t i2c_waitiflg(void);
+static void i2c_clriflg(void);
+static void i2c_start(void);
+static void i2c_stop(void);
+static int i2c_sendaddr(struct ez80_i2cdev_s *priv, uint8_t readbit);
+
+/* I2C methods */
+
+static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency);
+static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits);
+static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen);
+static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen);
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/* This function is normally prototyped int the ZiLOG header file sio.h */
+
+extern uint32_t get_freq(void);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static uint8_t g_currccr; /* Current setting of I2C CCR register */
+static bool g_initialized; /* true:I2C has been initialized */
+static sem_t g_i2csem; /* Serialize I2C transfers */
+
+const struct i2c_ops_s g_ops =
+{
+ i2c_setfrequency,
+ i2c_setaddress,
+ i2c_write,
+ i2c_read,
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: i2c_semtake/i2c_semgive
+ *
+ * Description:
+ * Take/Give the I2C semaphore.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void i2c_semtake(void)
+{
+ /* Take the I2C semaphore (perhaps waiting) */
+
+ while (sem_wait(&g_i2csem) != 0)
+ {
+ /* The only case that an error should occr here is if
+ * the wait was awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+#define i2c_semgive() sem_post(&g_i2csem)
+
+/****************************************************************************
+ * Name: i2c_setccr
+ *
+ * Description:
+ * Set the current BRG value for this transaction
+ *
+ * Input Parameters:
+ * ccr - BRG to set
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void i2c_setccr(uint16_t ccr)
+{
+ if (g_currccr != ccr)
+ {
+ outp(EZ80_I2C_CCR, ccr);
+ g_currccr = ccr;
+ }
+}
+
+/****************************************************************************
+ * Name: i2c_getccr
+ *
+ * Description:
+ * Calculate the BRG value
+ *
+ * Input Parameters:
+ * fscl - The I2C frequency requested
+ *
+ * Returned Value:
+ * Returns the actual frequency selected
+ *
+ ****************************************************************************/
+
+static uint16_t i2c_getccr(uint32_t fscl)
+{
+ uint32_t fsamp;
+ uint32_t ftmp;
+ uint8_t n;
+ uint8_t m;
+
+ /* The sampling frequency is given by:
+ *
+ * fsamp = sysclock / 2**N
+ *
+ * And the I2C clock is determined by:
+ *
+ * fscl = sysclock / 10 / (M + 1) / 2**N
+ * = fsamp / 10 / (M + 1)
+ *
+ * The fsmp must be >= 10 * fscl. The best solution is the smallest value of
+ * N so that the sampling rate is the highest subject to:
+ *
+ * The minimum value of the fsamp is given by:
+ */
+
+ fsamp = 10 * fscl;
+
+ /* Now, serarch for the smallest value of N that results in the actual
+ * fsamp >= the ideal fsamp. Fortunately, we only have to check at most
+ * eight values.
+ */
+
+ if (fsamp >= EZ80_SYS_CLK_FREQ)
+ {
+ ftmp = EZ80_SYS_CLK_FREQ / 10;
+ n = 0;
+ }
+ else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 1))
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 1) / 10;
+ n = 1;
+ }
+ else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 2))
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 2) / 10;
+ n = 2;
+ }
+ else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 3))
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 3) / 10;
+ n = 3;
+ }
+ else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 4))
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 4) / 10;
+ n = 4;
+ }
+ else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 5))
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 5) / 10;
+ n = 5;
+ }
+ else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 6))
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 6) / 10;
+ n = 6;
+ }
+ else if (fsamp >= (EZ80_SYS_CLK_FREQ >> 7))
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 7) / 10;
+ n = 7;
+ }
+ else
+ {
+ ftmp = (EZ80_SYS_CLK_FREQ >> 7) / 10;
+ fscl = ftmp;
+ n = 7;
+ }
+
+ /* Finally, get M:
+ *
+ * M = (fsamp / 10) / fscl - 1 = ftmp / fscl - 1
+ */
+
+ m = ftmp / fscl;
+ if (m > 0)
+ {
+ if (--m > 15)
+ {
+ m = 15;
+ }
+ }
+
+ /* Return the value for CCR */
+
+ return (n << I2C_CCR_NSHIFT) | (m << I2C_CCR_MSHIFT);
+}
+
+/****************************************************************************
+ * Name: i2c_waitiflg
+ *
+ * Description:
+ * In polled mode, we have to spin until the IFLG bit in the xxx register
+ * goes to 1, signalling that the last send or receive is complete. This
+ * could be used to generate an interrupt for a non-polled driver.
+ *
+ * Input Parameters:
+ * priv - Device-specific state data
+ * readbit - 0 or I2C_READBIT
+ *
+ * Returned Value:
+ * The contents of the I2C_SR register at the time that IFLG became 1.
+ *
+ ****************************************************************************/
+
+static uint8_t i2c_waitiflg(void)
+{
+ while ((inp(EZ80_I2C_CTL) & I2C_CTL_IFLG) != 0);
+ return inp(EZ80_I2C_SR);
+}
+
+/****************************************************************************
+ * Name: i2c_clriflg
+ *
+ * Description:
+ * Clear the IFLAG bit in the I2C_CTL register, acknowledging the event.
+ * If interrupts are enabled, this would clear the interrupt status.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void i2c_clriflg(void)
+{
+ uint8_t regval = inp(EZ80_I2C_CTL);
+ regval &= ~I2C_CTL_IFLG;
+ outp(EZ80_I2C_CTL, regval);
+}
+
+/****************************************************************************
+ * Name: i2c_start
+ *
+ * Description:
+ * Send the START bit. IFLAG must be zero; it will go to 1 when it is
+ * time to send the address.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void i2c_start(void)
+{
+ uint8_t regval = inp(EZ80_I2C_CTL);
+ regval |= I2C_CTL_STA;
+ outp(EZ80_I2C_CTL, regval);
+}
+
+/****************************************************************************
+ * Name: i2c_stop
+ *
+ * Description:
+ * Send the STOP bit. This terminates the I2C transfer and reverts back
+ * to IDLE mode.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void i2c_stop(void)
+{
+ uint8_t regval = inp(EZ80_I2C_CTL);
+ regval |= I2C_CTL_STP;
+ outp(EZ80_I2C_CTL, regval);
+}
+
+/****************************************************************************
+ * Name: i2c_sendaddr
+ *
+ * Description:
+ * Send the 8- or 11-bit address for either a read or a write transaction.
+ *
+ * Input Parameters:
+ * priv - Device-specific state data
+ * readbit - 0 or I2C_READBIT
+ *
+ * Returned Value:
+ * 0: Success, IFLG is set and DATA can be sent or received.
+
+ * Or <0: Negated error value. IFLG is cleared.
+ *
+ * -EIO: Irrecoverable (or unexpected) error occured
+ * -EAGAIN: And
+ *
+ ****************************************************************************/
+
+static int i2c_sendaddr(struct ez80_i2cdev_s *priv, uint8_t readbit)
+{
+ uint8_t sr;
+ int ret = OK;
+
+ /* Wait for the IFLG bit to transition to 1. At this point, we should
+ * have status == 8 meaning that the start bit was sent successfully.
+ */
+
+ sr = i2c_waitiflg();
+#ifdef CONFIG_DEBUG
+ if (sr != I2C_SR_MSTART)
+ {
+ /* This error should never occur */
+
+ dbg("Bad START status: %02x\n", sr);
+ i2c_clriflg();
+ return -EIO;
+ }
+#endif
+
+ /* Now send the address */
+
+ if (!priv->addr10)
+ {
+ /* Load the I2C_DR with the 8-bit I2C slave address and clear the
+ * IFLG. Clearing the IFLAG will cause the address to be transferred.
+ */
+
+ outp(EZ80_I2C_DR, (uint8_t)I2C_ADDR8(priv->addr) | readbit);
+ i2c_clriflg();
+
+ /* And wait for the address transfer to complete */
+
+ sr = i2c_waitiflg();
+ if (sr != I2C_SR_MADDRWRACK && sr != I2C_SR_MADDRWR)
+ {
+ dbg("Bad ADDR8 status: %02x\n", sr);
+ goto failure;
+ }
+ }
+ else
+ {
+ /* Load the I2C_DR with upper part of the 10->16-bit I2C slave address
+ * and clear the IFLG. Clearing the IFLAG will cause the address to
+ * be transferred.
+ */
+
+ outp(EZ80_I2C_DR, (uint8_t)I2C_ADDR10H(priv->addr) | readbit);
+ i2c_clriflg();
+
+ /* And wait for the address transfer to complete */
+
+ sr = i2c_waitiflg();
+ if (sr != I2C_SR_MADDRWRACK && sr != I2C_SR_MADDRWR)
+ {
+ dbg("Bad ADDR10H status: %02x\n", sr);
+ goto failure;
+ }
+
+ /* Now send the lower 8 bits of the 10-bit address */
+
+ outp(EZ80_I2C_DR, (uint8_t)I2C_ADDR10L(priv->addr));
+ i2c_clriflg();
+
+ /* And wait for the address transfer to complete */
+
+ sr = i2c_waitiflg();
+ if (sr != I2C_SR_MADDR2WRACK && sr != I2C_SR_MADDR2WR)
+ {
+ dbg("Bad ADDR10L status: %02x\n", sr);
+ goto failure;
+ }
+ }
+
+ return OK;
+
+ /* We don't attempt any fancy status-based error recovery */
+
+failure:
+#ifdef CONFIG_DEBUG
+ switch (sr)
+ {
+ case I2C_SR_ARBLOST1: /* Arbitration lost in address or data byte */
+ case I2C_SR_ARBLOST2: /* Arbitration lost in address as master, slave address and Write bit received, ACK transmitted */
+ case I2C_SR_ARBLOST3: /* Arbitration lost in address as master, General Call address received, ACK transmitted */
+ case I2C_SR_ARBLOST4: /* Arbitration lost in address as master, slave address and Read bit received, ACK transmitted */
+ dbg("Arbitration lost: %02x\n", sr);
+ i2c_clriflg();
+ return -EAGAIN;
+
+ default:
+ dbg("Unexpected status: %02x\n", sr);
+ i2c_clriflg();
+ return -EIO;
+ }
+#else
+ i2c_clriflg();
+ return -EAGAIN;
+#endif
+}
+
+/****************************************************************************
+ * Name: i2c_setfrequency
+ *
+ * Description:
+ * Set the I2C frequency. This frequency will be retained in the struct
+ * i2c_dev_s instance and will be used with all transfers. Required.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * frequency - The I2C frequency requested
+ *
+ * Returned Value:
+ * Returns the actual frequency selected
+ *
+ ****************************************************************************/
+
+static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency)
+{
+ FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
+
+ /* Sanity Check */
+
+#ifdef CONFIG_DEBUG
+ if (!dev)
+ {
+ dbg("Invalid inputs\n");
+ return -EINVAL;
+ }
+#endif
+
+ /* Calculate and save the BRG (we won't apply it until the first transfer) */
+
+ priv->ccr = i2c_getccr(frequency);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: i2c_setaddress
+ *
+ * Description:
+ * Set the I2C slave address. This frequency will be retained in the struct
+ * i2c_dev_s instance and will be used with all transfers. Required.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * address - The I2C slave address
+ * nbits - The number of address bits provided (7 or 10)
+ *
+ * Returned Value:
+ * Returns the actual frequency selected
+ *
+ ****************************************************************************/
+
+static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits)
+{
+ FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
+
+ /* Sanity Check */
+
+#ifdef CONFIG_DEBUG
+ if (!dev || (unsigned)addr > 0x7f || (nbits != 7 && nbits != 10))
+ {
+ dbg("Invalid inputs\n");
+ return -EINVAL;
+ }
+#endif
+
+ /* Save the 7- or 10-bit address */
+
+ priv->addr = addr;
+ priv->addr10 = (nbits == 10);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: i2c_write
+ *
+ * Description:
+ * Send a block of data on I2C using the previously selected I2C
+ * frequency and slave address. Each write operational will be an 'atomic'
+ * operation in the sense that any other I2C actions will be serialized
+ * and pend until this write completes. Required.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * buffer - A pointer to the read-only buffer of data to be written to device
+ * buflen - The number of bytes to send from the buffer
+ *
+ * Returned Value:
+ * 0: success, <0: A negated errno
+ *
+ ****************************************************************************/
+
+static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen)
+{
+ FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
+ const uint8_t *ptr;
+ uint8_t sr;
+ int retry;
+ int count;
+ int ret;
+
+#ifdef CONFIG_DEBUG
+ if (!priv || !buffer || buflen < 1)
+ {
+ dbg("Invalid inputs\n");
+ return -EINVAL;
+ }
+#endif
+
+ /* Get exclusive access */
+
+ i2c_semtake();
+
+ /* Set the frequency */
+
+ i2c_setccr(priv->ccr);
+
+ /* Retry as necessary to send this whole message */
+
+ for (retry = 0; retry < 100; retry++)
+ {
+ /* Enter MASTER TRANSMIT mode by setting the STA bit in the I2C_CTL
+ * register to 1. The I2C then tests the I2C bus and transmits a START
+ * condition when the bus is free.
+ */
+
+ i2c_start();
+
+ /* When a START condition is transmitted, the IFLG bit is 1. Then we may
+ * send the I2C slave address.
+ */
+
+ ret = i2c_sendaddr(priv, 0);
+ if (ret < 0)
+ {
+ if (ret == -EAGAIN)
+ {
+ continue;
+ }
+ else
+ {
+ goto failure;
+ }
+ }
+
+ /* Then send all of the bytes in the buffer */
+
+ ptr = buffer;
+ for (count = buflen; count; count--)
+ {
+ /* Load the I2C_DR with next data byte and clear the IFLG. Clearing
+ * the IFLAG will cause the data to be transferred.
+ */
+
+ outp(EZ80_I2C_DR, *ptr++);
+ i2c_clriflg();
+
+ /* And wait for the data transfer to complete */
+
+ sr = i2c_waitiflg();
+ if (sr != I2C_SR_MDATAWRACK && sr != I2C_SR_MDATAWR)
+ {
+ dbg("Bad DATA status: %02x\n", sr);
+ i2c_clriflg();
+ if (sr == I2C_SR_ARBLOST1)
+ {
+ /* Arbitration lost, break out of the inner loop and
+ * try sending the message again
+ */
+
+ break;
+ }
+
+ /* Otherwise, it is fatal (shouldn't happen) */
+
+ ret = -EIO;
+ goto failure;
+ }
+
+ /* Data byte was sent successfully. Was that the last byte? */
+
+ else if (count <= 1)
+ {
+ /* When all bytes are transmitted, the microcontroller must
+ * write a 1 to the STP bit in the I2C_CTL register. The
+ * I2C then transmits a STOP condition, clears the STP bit
+ * and returns to an idle state.
+ */
+
+ i2c_stop();
+
+ ret = OK;
+ goto success;
+ }
+ }
+ }
+
+ /* If we get here, we timed out without successfully sending the message */
+
+ ret = -ETIMEDOUT;
+
+success:
+failure:
+ i2c_semgive();
+ return ret;
+}
+
+/****************************************************************************
+ * Name: i2c_read
+ *
+ * Description:
+ * Receive a block of data from I2C using the previously selected I2C
+ * frequency and slave address. Each read operational will be an 'atomic'
+ * operation in the sense that any other I2C actions will be serialized
+ * and pend until this read completes. Required.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * buffer - A pointer to a buffer of data to receive the data from the device
+ * buflen - The requested number of bytes to be read
+ *
+ * Returned Value:
+ * 0: success, <0: A negated errno
+ *
+ ****************************************************************************/
+
+static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen)
+{
+ FAR struct ez80_i2cdev_s *priv = (FAR struct ez80_i2cdev_s *)dev;
+ uint8_t *ptr;
+ uint8_t regval;
+ int retry;
+ int count;
+ int ret;
+
+#ifdef CONFIG_DEBUG
+ if (!priv || !buffer || buflen < 1)
+ {
+ dbg("Invalid inputs\n");
+ return -EINVAL;
+ }
+#endif
+
+ /* Get exclusive access */
+
+ i2c_semtake();
+
+ /* Set the frequency */
+
+ i2c_setccr(priv->ccr);
+
+ /* Retry as necessary to receive the whole message */
+
+ for (retry = 0; retry < 100; retry++)
+ {
+ /* Enter MASTER TRANSMIT mode by setting the STA bit in the I2C_CTL
+ * register to 1. The I2C then tests the I2C bus and transmits a START
+ * condition when the bus is free.
+ */
+
+ i2c_start();
+
+ /* When a START condition is transmitted, the IFLG bit is 1. Then we may
+ * send the I2C slave address.
+ */
+
+ ret = i2c_sendaddr(priv, 0);
+ if (ret < 0)
+ {
+ if (ret == -EAGAIN)
+ {
+ continue;
+ }
+ else
+ {
+ goto failure;
+ }
+ }
+
+ /* Now loop to receive each data byte */
+
+ ptr = buffer;
+ for (count = buflen; count; count--)
+ {
+ /* Is this the last byte? If so, we must NACK it */
+
+ regval = inp(EZ80_I2C_CTL);
+ if (count <= 1)
+ {
+ /* If the AAK bit is cleared to 0 during a transfer, the I2C
+ * transmits a NACK bit after the next byte is received.
+ */
+
+ regval &= ~I2C_CTL_AAK;
+ }
+ else
+ {
+ /* If the AAK bit in the I2C_CTL register is set to 1 then an
+ * ACK bit is transmitted and the IFLG bit is set after each
+ * byte is received.
+ */
+
+ regval |= I2C_CTL_AAK;
+ }
+ outp(EZ80_I2C_CTL, regval);
+
+ /* Wait for IFLG to be set meaning that incoming data is
+ * available in the I2C_DR registers.
+ */
+
+ regval = i2c_waitiflg();
+
+ /* Data byte received in MASTER mode, ACK transmitted */
+
+ if (regval == I2C_SR_MDATARDACK)
+ {
+ /* Since we just ACKed the incoming byte, it must NOT be the last */
+
+ DEBUGASSERT(count > 1);
+
+ /* Receive the data and clear the IFLGS */
+
+ *ptr++ = inp(EZ80_I2C_DR);
+ i2c_clriflg();
+ }
+
+ /* Data byte received in MASTER mode, NACK transmitted */
+
+ else if (regval == I2C_SR_MDATARDNAK)
+ {
+ /* Since we just NACKed the incoming byte, it must be the last */
+
+ DEBUGASSERT(count <= 1);
+
+ /* When all bytes are received and the NACK has been sent, then the
+ * microcontroller must write 1 to the STP bit in the I2C_CTL
+ * register. The I2C then transmits a STOP condition, clears
+ * the STP bit and returns to an idle state.
+ */
+
+ i2c_stop();
+ i2c_clriflg();
+
+ ret = OK;
+ goto success;
+ }
+
+ /* Arbitration lost in address or data byte */
+
+ else if (regval == I2C_SR_ARBLOST1)
+ {
+ /* Clear the IFLG and break out of the inner loop.
+ * this will cause the whole transfer to start over
+ */
+
+ dbg("Arbitration lost: %02x\n", regval);
+ i2c_clriflg();
+ break;
+ }
+
+ /* Unexpected status response */
+
+ else
+ {
+ dbg("Unexpected status: %02x\n", regval);
+ i2c_clriflg();
+ ret = -EIO;
+ goto failure;
+ }
+ }
+ }
+ ret = -ETIMEDOUT;
+
+success:
+failure:
+ i2c_semgive();
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_i2cinitialize
+ *
+ * Description:
+ * Initialize the selected I2C port. And return a unique instance of struct
+ * struct i2c_dev_s. This function may be called to obtain multiple
+ * instances of the interface, each of which may be set up with a
+ * different frequency and slave address.
+ *
+ * Input Parameter:
+ * Port number (for hardware that has mutiple I2C interfaces)
+ *
+ * Returned Value:
+ * Valid I2C device structre reference on succcess; a NULL on failure
+ *
+ ****************************************************************************/
+
+FAR struct i2c_dev_s *up_i2cinitialize(int port)
+{
+ FAR struct ez80_i2cdev_s *i2c;
+ uint16_t ccr;
+ uint8_t regval;
+
+ if (!g_initialized)
+ {
+ /* Set up some initial BRG value */
+
+ ccr = i2c_getccr(100*1000);
+ i2c_setccr(ccr);
+
+ /* No GPIO setup is required -- I2C pints, SCL/SDA are not multiplexed */
+
+ /* This semaphore enforces serialized access for I2C transfers */
+
+ sem_init(&g_i2csem, 0, 1);
+
+ /* Enable I2C -- but not interrupts */
+
+ regval = inp(EZ80_I2C_CTL);
+ regval |= I2C_CTL_ENAB;
+ outp(EZ80_I2C_CTL, regval);
+ }
+
+ /* Now, allocate an I2C instance for this caller */
+
+ i2c = (FAR struct ez80_i2cdev_s *)malloc(sizeof(FAR struct ez80_i2cdev_s));
+ if (i2c)
+ {
+ /* Initialize the allocated instance */
+
+ i2c->ops = &g_ops;
+ i2c->ccr = g_currccr;
+ }
+ return (FAR struct i2c_dev_s *)i2c;
+}
diff --git a/nuttx/arch/z80/src/ez80/ez80_initialstate.c b/nuttx/arch/z80/src/ez80/ez80_initialstate.c
index 68ff517a9..5b6e5fb4b 100644
--- a/nuttx/arch/z80/src/ez80/ez80_initialstate.c
+++ b/nuttx/arch/z80/src/ez80/ez80_initialstate.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_initialstate.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 <string.h>
#include <nuttx/arch.h>
@@ -85,7 +85,7 @@ void up_initial_state(_TCB *tcb)
memset(xcp, 0, sizeof(struct xcptcontext));
#ifndef CONFIG_SUPPRESS_INTERRUPTS
- ((ubyte*)xcp->regs)[XCPT_IF_OFFSET] = EZ80_PV_FLAG; /* Parity/Overflow flag will enable interrupts */
+ ((uint8_t*)xcp->regs)[XCPT_IF_OFFSET] = EZ80_PV_FLAG; /* Parity/Overflow flag will enable interrupts */
#endif
xcp->regs[XCPT_SP] = (chipreg_t)tcb->adj_stack_ptr;
xcp->regs[XCPT_PC] = (chipreg_t)tcb->start;
diff --git a/nuttx/arch/z80/src/ez80/ez80_io.asm b/nuttx/arch/z80/src/ez80/ez80_io.asm
index 86af3b3e8..9c5d28e7e 100644
--- a/nuttx/arch/z80/src/ez80/ez80_io.asm
+++ b/nuttx/arch/z80/src/ez80/ez80_io.asm
@@ -1,7 +1,7 @@
;**************************************************************************
; arch/z80/src/ze80/ez80_io.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
@@ -58,7 +58,7 @@
.assume ADL=1
;**************************************************************************
-; Name: void outp(uint16 p, ubyte c)
+; Name: void outp(uint16_t p, uint8_t c)
;
; Description:
; Output byte c on port p
@@ -108,7 +108,7 @@ _outp:
ret
;**************************************************************************
-; Name: ubyte inp(uint16 p)
+; Name: uint8_t inp(uint16_t p)
;
; Description:
; Input byte from port p
diff --git a/nuttx/arch/z80/src/ez80/ez80_irq.c b/nuttx/arch/z80/src/ez80/ez80_irq.c
index 6e0fa71c6..38a51c9c4 100644
--- a/nuttx/arch/z80/src/ez80/ez80_irq.c
+++ b/nuttx/arch/z80/src/ez80/ez80_irq.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_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,6 @@
#include <nuttx/config.h>
-#include <sys/types.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
diff --git a/nuttx/arch/z80/src/ez80/ez80_lowuart.c b/nuttx/arch/z80/src/ez80/ez80_lowuart.c
index a89c8089b..5bcbaa043 100644
--- a/nuttx/arch/z80/src/ez80/ez80_lowuart.c
+++ b/nuttx/arch/z80/src/ez80/ez80_lowuart.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_loweruart.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 <string.h>
#include <arch/io.h>
@@ -140,8 +140,8 @@
#if defined(HAVE_SERIALCONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
static void ez80_setbaud(void)
{
- uint32 brg_divisor;
- ubyte lctl;
+ uint32_t brg_divisor;
+ uint8_t lctl;
/* The resulting BAUD and depends on the system clock frequency and the
* BRG divisor as follows:
@@ -163,8 +163,8 @@ static void ez80_setbaud(void)
lctl |= EZ80_UARTLCTL_DLAB;
ez80_outp(EZ80_UART_LCTL, lctl);
- ez80_outp(EZ80_UART_BRGL, (ubyte)(brg_divisor & 0xff));
- ez80_outp(EZ80_UART_BRGH, (ubyte)(brg_divisor >> 8));
+ ez80_outp(EZ80_UART_BRGL, (uint8_t)(brg_divisor & 0xff));
+ ez80_outp(EZ80_UART_BRGH, (uint8_t)(brg_divisor >> 8));
lctl &= ~EZ80_UARTLCTL_DLAB;
ez80_outp(EZ80_UART_LCTL, lctl);
@@ -182,7 +182,7 @@ static void ez80_setbaud(void)
void up_lowuartinit(void)
{
#ifdef HAVE_SERIAL
- ubyte regval;
+ uint8_t regval;
/* Configure pins for usage of UARTs (whether or not we have a console) */
diff --git a/nuttx/arch/z80/src/ez80/ez80_registerdump.c b/nuttx/arch/z80/src/ez80/ez80_registerdump.c
index 31a69679c..d1aa3726b 100644
--- a/nuttx/arch/z80/src/ez80/ez80_registerdump.c
+++ b/nuttx/arch/z80/src/ez80/ez80_registerdump.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_registerdump.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/irq.h>
diff --git a/nuttx/arch/z80/src/ez80/ez80_schedulesigaction.c b/nuttx/arch/z80/src/ez80/ez80_schedulesigaction.c
index 0ca61a6ff..e95cebc69 100644
--- a/nuttx/arch/z80/src/ez80/ez80_schedulesigaction.c
+++ b/nuttx/arch/z80/src/ez80/ez80_schedulesigaction.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_schedulesigaction.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>
@@ -123,7 +123,7 @@ static void ez80_sigsetup(FAR _TCB *tcb, sig_deliver_t sigdeliver, FAR chipreg_t
void up_schedule_sigaction(FAR _TCB *tcb, sig_deliver_t sigdeliver)
{
- sdbg("tcb=0x%p sigdeliver=0x%04x\n", tcb, (uint16)sigdeliver);
+ sdbg("tcb=0x%p sigdeliver=0x%04x\n", tcb, (uint16_t))sigdeliver);
/* Refuse to handle nested signal actions */
diff --git a/nuttx/arch/z80/src/ez80/ez80_serial.c b/nuttx/arch/z80/src/ez80/ez80_serial.c
index e8e0ec0a0..e5fefbd87 100644
--- a/nuttx/arch/z80/src/ez80/ez80_serial.c
+++ b/nuttx/arch/z80/src/ez80/ez80_serial.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez08/ez80_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
@@ -40,6 +40,8 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
#include <unistd.h>
#include <semaphore.h>
#include <string.h>
@@ -68,31 +70,31 @@
struct ez80_dev_s
{
- uint16 uartbase; /* Base address of UART registers */
- unsigned int baud; /* Configured baud */
- ubyte irq; /* IRQ associated with this UART */
- ubyte parity; /* 0=none, 1=odd, 2=even */
- ubyte bits; /* Number of bits (7 or 8) */
- boolean stopbits2; /* TRUE: Configure with 2 (vs 1) */
+ uint16_t uartbase; /* Base address of UART registers */
+ unsigned int baud; /* Configured baud */
+ uint8_t irq; /* IRQ associated with this UART */
+ uint8_t parity; /* 0=none, 1=odd, 2=even */
+ uint8_t bits; /* Number of bits (7 or 8) */
+ bool stopbits2; /* true: Configure with 2 (vs 1) */
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-static int ez80_setup(struct uart_dev_s *dev);
-static void ez80_shutdown(struct uart_dev_s *dev);
-static int ez80_attach(struct uart_dev_s *dev);
-static void ez80_detach(struct uart_dev_s *dev);
-static int ez80_interrrupt(int irq, void *context);
-static int ez80_ioctl(struct file *filep, int cmd, unsigned long arg);
-static int ez80_receive(struct uart_dev_s *dev, unsigned int *status);
-static void ez80_rxint(struct uart_dev_s *dev, boolean enable);
-static boolean ez80_rxavailable(struct uart_dev_s *dev);
-static void ez80_send(struct uart_dev_s *dev, int ch);
-static void ez80_txint(struct uart_dev_s *dev, boolean enable);
-static boolean ez80_txready(struct uart_dev_s *dev);
-static boolean ez80_txempty(struct uart_dev_s *dev);
+static int ez80_setup(struct uart_dev_s *dev);
+static void ez80_shutdown(struct uart_dev_s *dev);
+static int ez80_attach(struct uart_dev_s *dev);
+static void ez80_detach(struct uart_dev_s *dev);
+static int ez80_interrrupt(int irq, void *context);
+static int ez80_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int ez80_receive(struct uart_dev_s *dev, unsigned int *status);
+static void ez80_rxint(struct uart_dev_s *dev, bool enable);
+static bool ez80_rxavailable(struct uart_dev_s *dev);
+static void ez80_send(struct uart_dev_s *dev, int ch);
+static void ez80_txint(struct uart_dev_s *dev, bool enable);
+static bool ez80_txready(struct uart_dev_s *dev);
+static bool ez80_txempty(struct uart_dev_s *dev);
/****************************************************************************
* Private Variables
@@ -141,12 +143,12 @@ static struct ez80_dev_s g_uart0priv =
static uart_dev_t g_uart0port =
{
0, /* open_count */
- FALSE, /* xmitwaiting */
- FALSE, /* recvwaiting */
+ false, /* xmitwaiting */
+ false, /* recvwaiting */
#ifdef CONFIG_UART0_SERIAL_CONSOLE
- TRUE, /* isconsole */
+ true, /* isconsole */
#else
- FALSE, /* isconsole */
+ false, /* isconsole */
#endif
{ 0 }, /* closesem */
{ 0 }, /* xmitsem */
@@ -186,12 +188,12 @@ static struct ez80_dev_s g_uart1priv =
static uart_dev_t g_uart1port =
{
0, /* open_count */
- FALSE, /* xmitwaiting */
- FALSE, /* recvwaiting */
+ false, /* xmitwaiting */
+ false, /* recvwaiting */
#ifdef CONFIG_UART1_SERIAL_CONSOLE
- TRUE, /* isconsole */
+ true, /* isconsole */
#else
- FALSE, /* isconsole */
+ false, /* isconsole */
#endif
{ 0 }, /* closesem */
{ 0 }, /* xmitsem */
@@ -246,7 +248,7 @@ static uart_dev_t g_uart1port =
* Name: ez80_serialin
****************************************************************************/
-static inline ubyte ez80_serialin(struct ez80_dev_s *priv, ubyte offset)
+static inline uint8_t ez80_serialin(struct ez80_dev_s *priv, uint8_t offset)
{
return inp(priv->uartbase + offset);
}
@@ -255,7 +257,8 @@ static inline ubyte ez80_serialin(struct ez80_dev_s *priv, ubyte offset)
* Name: ez80_serialout
****************************************************************************/
-static inline void ez80_serialout(struct ez80_dev_s *priv, ubyte offset, ubyte value)
+static inline void ez80_serialout(struct ez80_dev_s *priv, uint8_t offset,
+ uint8_t value)
{
outp(priv->uartbase + offset, value);
}
@@ -266,7 +269,7 @@ static inline void ez80_serialout(struct ez80_dev_s *priv, ubyte offset, ubyte v
static inline void ez80_disableuartint(struct ez80_dev_s *priv)
{
- ubyte ier = ez80_serialin(priv, EZ80_UART_IER);
+ uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
ier &= ~EZ80_UARTEIR_INTMASK;
ez80_serialout(priv, EZ80_UART_IER, ier);
}
@@ -275,9 +278,9 @@ static inline void ez80_disableuartint(struct ez80_dev_s *priv)
* Name: ez80_restoreuartint
****************************************************************************/
-static inline void ez80_restoreuartint(struct ez80_dev_s *priv, ubyte bits)
+static inline void ez80_restoreuartint(struct ez80_dev_s *priv, uint8_t bits)
{
- ubyte ier = ez80_serialin(priv, EZ80_UART_IER);
+ uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
ier |= bits & (EZ80_UARTEIR_TIE|EZ80_UARTEIR_RIE);
ez80_serialout(priv, EZ80_UART_IER, ier);
}
@@ -303,10 +306,10 @@ static inline void ez80_waittxready(struct ez80_dev_s *priv)
* Name: ez80_setbaud
****************************************************************************/
-static inline void ez80_setbaud(struct ez80_dev_s *priv, uint24 baud)
+static inline void ez80_setbaud(struct ez80_dev_s *priv, uint24_t baud)
{
- uint32 brg_divisor;
- ubyte lctl;
+ uint32_t brg_divisor;
+ uint8_t lctl;
/* The resulting BAUD and depends on the system clock frequency and the
* BRG divisor as follows:
@@ -326,8 +329,8 @@ static inline void ez80_setbaud(struct ez80_dev_s *priv, uint24 baud)
lctl |= EZ80_UARTLCTL_DLAB;
ez80_serialout(priv, EZ80_UART_LCTL, lctl);
- ez80_serialout(priv, EZ80_UART_BRGL, (ubyte)(brg_divisor & 0xff));
- ez80_serialout(priv, EZ80_UART_BRGH, (ubyte)(brg_divisor >> 8));
+ ez80_serialout(priv, EZ80_UART_BRGL, (uint8_t)(brg_divisor & 0xff));
+ ez80_serialout(priv, EZ80_UART_BRGH, (uint8_t)(brg_divisor >> 8));
lctl &= ~EZ80_UARTLCTL_DLAB;
ez80_serialout(priv, EZ80_UART_LCTL, lctl);
@@ -346,8 +349,8 @@ static int ez80_setup(struct uart_dev_s *dev)
{
#ifndef CONFIG_SUPPRESS_UART_CONFIG
struct ez80_dev_s *priv = dev->priv;
- ubyte reg;
- ubyte cval;
+ uint8_t reg;
+ uint8_t cval;
if (priv->bits == 7)
{
@@ -441,8 +444,8 @@ static int ez80_attach(struct uart_dev_s *dev)
*
* Description:
* Detach UART interrupts. This method is called when the serial port is
- * closed normally just before the shutdown method is called. The exception is
- * the serial console which is never shutdown.
+ * closed normally just before the shutdown method is called. The exception
+ * is the serial console which is never shutdown.
*
****************************************************************************/
@@ -470,7 +473,7 @@ static int ez80_interrrupt(int irq, void *context)
{
struct uart_dev_s *dev = NULL;
struct ez80_dev_s *priv;
- volatile uint32 cause;
+ volatile uint32_t cause;
#ifndef CONFIG_UART0_DISABLE
if (g_uart0priv.irq == irq)
@@ -539,8 +542,8 @@ static int ez80_ioctl(struct file *filep, int cmd, unsigned long arg)
static int ez80_receive(struct uart_dev_s *dev, unsigned int *status)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
- ubyte rbr = ez80_serialin(priv, EZ80_UART_RBR);
- ubyte lsr = ez80_serialin(priv, EZ80_UART_LSR);
+ uint8_t rbr = ez80_serialin(priv, EZ80_UART_RBR);
+ uint8_t lsr = ez80_serialin(priv, EZ80_UART_LSR);
*status = (unsigned int)lsr;
return rbr;
@@ -554,10 +557,10 @@ static int ez80_receive(struct uart_dev_s *dev, unsigned int *status)
*
****************************************************************************/
-static void ez80_rxint(struct uart_dev_s *dev, boolean enable)
+static void ez80_rxint(struct uart_dev_s *dev, bool enable)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
- ubyte ier = ez80_serialin(priv, EZ80_UART_IER);
+ uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
if (enable)
{
@@ -577,11 +580,11 @@ static void ez80_rxint(struct uart_dev_s *dev, boolean enable)
* Name: ez80_rxavailable
*
* Description:
- * Return TRUE if the receive fifo is not empty
+ * Return true if the receive fifo is not empty
*
****************************************************************************/
-static boolean ez80_rxavailable(struct uart_dev_s *dev)
+static bool ez80_rxavailable(struct uart_dev_s *dev)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
return (ez80_serialin(priv, EZ80_UART_LSR) & EZ80_UARTLSR_DR) != 0;
@@ -598,7 +601,7 @@ static boolean ez80_rxavailable(struct uart_dev_s *dev)
static void ez80_send(struct uart_dev_s *dev, int ch)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
- ez80_serialout(priv, EZ80_UART_THR, (ubyte)ch);
+ ez80_serialout(priv, EZ80_UART_THR, (uint8_t)ch);
}
/****************************************************************************
@@ -609,10 +612,10 @@ static void ez80_send(struct uart_dev_s *dev, int ch)
*
****************************************************************************/
-static void ez80_txint(struct uart_dev_s *dev, boolean enable)
+static void ez80_txint(struct uart_dev_s *dev, bool enable)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
- ubyte ier = ez80_serialin(priv, EZ80_UART_IER);
+ uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
if (enable)
{
@@ -632,11 +635,11 @@ static void ez80_txint(struct uart_dev_s *dev, boolean enable)
* Name: ez80_txready
*
* Description:
- * Return TRUE if the tranmsit fifo is not full
+ * Return true if the tranmsit fifo is not full
*
****************************************************************************/
-static boolean ez80_txready(struct uart_dev_s *dev)
+static bool ez80_txready(struct uart_dev_s *dev)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
return (ez80_serialin(priv, EZ80_UART_LSR) & EZ80_UARTLSR_THRE) != 0;
@@ -646,11 +649,11 @@ static boolean ez80_txready(struct uart_dev_s *dev)
* Name: ez80_txempty
*
* Description:
- * Return TRUE if the transmit fifo is empty
+ * Return true if the transmit fifo is empty
*
****************************************************************************/
-static boolean ez80_txempty(struct uart_dev_s *dev)
+static bool ez80_txempty(struct uart_dev_s *dev)
{
struct ez80_dev_s *priv = (struct ez80_dev_s*)dev->priv;
return (ez80_serialin(priv, EZ80_UART_LSR) & EZ80_UARTLSR_TEMT) != 0;
@@ -670,7 +673,7 @@ static boolean ez80_txempty(struct uart_dev_s *dev)
void up_serialinit(void)
{
- ubyte regval;
+ uint8_t regval;
/* Make sure that all UART interrupts are disabled */
@@ -716,7 +719,7 @@ void up_serialinit(void)
/* If there is a console, then configure the console now */
#ifdef CONSOLE_DEV
- CONSOLE_DEV.isconsole = TRUE;
+ CONSOLE_DEV.isconsole = true;
ez80_setup(&CONSOLE_DEV);
#endif
@@ -744,7 +747,7 @@ int up_putc(int ch)
{
#ifdef CONSOLE_DEV
struct ez80_dev_s *priv = (struct ez80_dev_s*)CONSOLE_DEV.priv;
- ubyte ier = ez80_serialin(priv, EZ80_UART_IER);
+ uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
ez80_disableuartint(priv);
@@ -761,7 +764,7 @@ int up_putc(int ch)
/* Output the character */
ez80_waittxready(priv);
- ez80_serialout(priv, EZ80_UART_THR, (ubyte)ch);
+ ez80_serialout(priv, EZ80_UART_THR, (uint8_t)ch);
/* Wait for the character to be sent before re-enabling interrupts */
diff --git a/nuttx/arch/z80/src/ez80/ez80_sigdeliver.c b/nuttx/arch/z80/src/ez80/ez80_sigdeliver.c
index 3f6b6ed1a..90fdf4c6b 100644
--- a/nuttx/arch/z80/src/ez80/ez80_sigdeliver.c
+++ b/nuttx/arch/z80/src/ez80/ez80_sigdeliver.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/z80/src/ez80/ez80_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,6 @@
#include <nuttx/config.h>
-#include <sys/types.h>
#include <sched.h>
#include <debug.h>
diff --git a/nuttx/arch/z80/src/ez80/ez80_spi.c b/nuttx/arch/z80/src/ez80/ez80_spi.c
index d051f074f..6c5f7f2aa 100755
--- a/nuttx/arch/z80/src/ez80/ez80_spi.c
+++ b/nuttx/arch/z80/src/ez80/ez80_spi.c
@@ -38,7 +38,9 @@
****************************************************************************/
#include <nuttx/config.h>
-#include <nuttx/spi.h>
+
+#include <sys/types.h>
+#include <stdint.h>
#include <arch/board/board.h>
#include <nuttx/arch.h>
@@ -65,11 +67,14 @@
* Private Function Prototypes
****************************************************************************/
-static uint32 spi_setfrequency(FAR struct spi_dev_s *dev, uint32 frequency);
+static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev,
+ uint32_t frequency);
static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
-static uint16 spi_send(FAR struct spi_dev_s *dev, uint16 wd);
-static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const ubyte *buffer, size_t buflen);
-static void spi_recvblock(FAR struct spi_dev_s *dev, FAR ubyte *buffer, size_t buflen);
+static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd);
+static void spi_sndblock(FAR struct spi_dev_s *dev,
+ FAR const uint8_t *buffer, size_t buflen);
+static void spi_recvblock(FAR struct spi_dev_s *dev, FAR uint8_t *buffer,
+ size_t buflen);
/****************************************************************************
* Private Data
@@ -119,7 +124,7 @@ static struct spi_dev_s g_spidev = { &g_spiops };
*
****************************************************************************/
-static uint32 spi_setfrequency(FAR struct spi_dev_s *dev, uint32 frequency)
+static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
{
/* We want select divisor to provide the highest frequency (SPIR) that does NOT
* exceed the requested frequency.:
@@ -131,7 +136,7 @@ static uint32 spi_setfrequency(FAR struct spi_dev_s *dev, uint32 frequency)
* BRG >= System Clock Frequency / (2 * SPIR)
*/
- uint32 brg = ((EZ80_SYS_CLK_FREQ+1)/2 + frequency - 1) / frequency;
+ uint32_t brg = ((EZ80_SYS_CLK_FREQ+1)/2 + frequency - 1) / frequency;
/* "When configured as a Master, the 16-bit divisor value must be between
* 0003h and FFFFh, inclusive. When configured as a Slave, the 16-bit
@@ -170,8 +175,8 @@ static uint32 spi_setfrequency(FAR struct spi_dev_s *dev, uint32 frequency)
static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
{
- ubyte modebits;
- ubyte regval;
+ uint8_t modebits;
+ uint8_t regval;
/* Select the CTL register bits based on the selected mode */
@@ -220,9 +225,9 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
*
****************************************************************************/
-static ubyte spi_waitspif(void)
+static uint8_t spi_waitspif(void)
{
- ubyte status;
+ uint8_t status;
/* Wait for the device to be ready to accept another byte (or for an error
* to be reported
@@ -250,9 +255,9 @@ static ubyte spi_waitspif(void)
*
****************************************************************************/
-static ubyte spi_transfer(ubyte ch)
+static uint8_t spi_transfer(uint8_t ch)
{
- ubyte status;
+ uint8_t status;
/* Send the byte, repeating if some error occurs */
@@ -286,9 +291,9 @@ static ubyte spi_transfer(ubyte ch)
*
****************************************************************************/
-static uint16 spi_send(FAR struct spi_dev_s *dev, uint16 wd)
+static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t wd)
{
- return spi_transfer((ubyte)wd);
+ return spi_transfer((uint8_t)wd);
}
/*************************************************************************
@@ -303,17 +308,19 @@ static uint16 spi_send(FAR struct spi_dev_s *dev, uint16 wd)
* buflen - the length of data to send from the buffer in number of words.
* The wordsize is determined by the number of bits-per-word
* selected for the SPI interface. If nbits <= 8, the data is
- * packed into ubytes; if nbits >8, the data is packed into uint16's
+ * packed into uint8_t's; if nbits >8, the data is packed into
+ * uint16_t's
*
* Returned Value:
* None
*
****************************************************************************/
-static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t buflen)
+static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer,
+ size_t buflen)
{
- FAR const ubyte *ptr = (FAR const ubyte*)buffer;
- ubyte response;
+ FAR const uint8_t *ptr = (FAR const uint8_t*)buffer;
+ uint8_t response;
/* Loop while thre are bytes remaining to be sent */
@@ -335,7 +342,8 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
* buflen - the length of data that can be received in the buffer in number
* of words. The wordsize is determined by the number of bits-per-word
* selected for the SPI interface. If nbits <= 8, the data is
- * packed into ubytes; if nbits >8, the data is packed into uint16's
+ * packed into uint8_t's; if nbits >8, the data is packed into
+ * uint16_t's
*
* Returned Value:
* None
@@ -344,8 +352,8 @@ static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t buflen)
{
- FAR ubyte *ptr = (FAR ubyte*)buffer;
- ubyte response;
+ FAR uint8_t *ptr = (FAR uint8_t*)buffer;
+ uint8_t response;
/* Loop while thre are bytes remaining to be sent */
@@ -383,7 +391,7 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t bu
FAR struct spi_dev_s *up_spiinitialize(int port)
{
- ubyte regval;
+ uint8_t regval;
/* Only the SPI1 interface is supported */
diff --git a/nuttx/arch/z80/src/ez80/ez80_timerisr.c b/nuttx/arch/z80/src/ez80/ez80_timerisr.c
index 51eb90ebe..b047a1331 100644
--- a/nuttx/arch/z80/src/ez80/ez80_timerisr.c
+++ b/nuttx/arch/z80/src/ez80/ez80_timerisr.c
@@ -1,7 +1,7 @@
/***************************************************************************
* arch/z80/src/ez80/ez80_timerisr.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 <arch/io.h>
@@ -76,7 +76,7 @@
int up_timerisr(int irq, chipreg_t *regs)
{
- volatile ubyte reg;
+ volatile uint8_t reg;
/* Read the appropropriate timer0 registr to clear the interrupt */
@@ -112,8 +112,8 @@ int up_timerisr(int irq, chipreg_t *regs)
void up_timerinit(void)
{
- uint16 reload;
- ubyte reg;
+ uint16_t) reload;
+ uint8_t reg;
/* Disable the timer */
@@ -142,9 +142,9 @@ void up_timerinit(void)
* NOTE: The system clock frequency value is defined in the board.h file
*/
- reload = (uint16)(ez80_systemclock / 1600);
- outp(EZ80_TMR0_RRH, (ubyte)(reload >> 8));
- outp(EZ80_TMR0_RRL, (ubyte)(reload));
+ reload = (uint16_t))(ez80_systemclock / 1600);
+ outp(EZ80_TMR0_RRH, (uint8_t)(reload >> 8));
+ outp(EZ80_TMR0_RRL, (uint8_t)(reload));
/* Clear any pending timer interrupts */
diff --git a/nuttx/arch/z80/src/ez80/ez80f91_emac.h b/nuttx/arch/z80/src/ez80/ez80f91_emac.h
index eee5a4571..61f2e7f5a 100644
--- a/nuttx/arch/z80/src/ez80/ez80f91_emac.h
+++ b/nuttx/arch/z80/src/ez80/ez80f91_emac.h
@@ -2,7 +2,7 @@
* arch/z80/src/ez80/ez80f91_emac.h
* arch/z80/src/chip/ez80f91_emac.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,6 +41,10 @@
* Included Files
************************************************************************************/
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
/************************************************************************************
* Definitions
************************************************************************************/
@@ -249,11 +253,11 @@
#ifndef __ASSEMBLY__
struct ez80emac_desc_s
{
- uint24 np; /* Pointer to the start of the next packet */
- uint16 pktsize; /* Number of bytes in the packet, including the 4 CRC
- * bytes, but excluding the 7 descriptor table bytes. */
- uint16 stat; /* Status of the packet. Differs for TX and RX packets
- * (see EMAC_RX/TXDESC_* definitions) */
+ uint24_t np; /* Pointer to the start of the next packet */
+ uint16_t pktsize; /* Number of bytes in the packet, including the 4 CRC
+ * bytes, but excluding the 7 descriptor table bytes. */
+ uint16_t stat; /* Status of the packet. Differs for TX and RX packets
+ * (see EMAC_RX/TXDESC_* definitions) */
};
#endif
diff --git a/nuttx/arch/z80/src/ez80/ez80f91_i2c.h b/nuttx/arch/z80/src/ez80/ez80f91_i2c.h
index b77e56ae4..20ffb513a 100644
--- a/nuttx/arch/z80/src/ez80/ez80f91_i2c.h
+++ b/nuttx/arch/z80/src/ez80/ez80f91_i2c.h
@@ -42,7 +42,6 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
/************************************************************************************
* Definitions
diff --git a/nuttx/arch/z80/src/ez80/ez80f91_spi.h b/nuttx/arch/z80/src/ez80/ez80f91_spi.h
index 5a0305b68..9e697cbbe 100644
--- a/nuttx/arch/z80/src/ez80/ez80f91_spi.h
+++ b/nuttx/arch/z80/src/ez80/ez80f91_spi.h
@@ -42,7 +42,8 @@
************************************************************************************/
#include <nuttx/config.h>
-#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
#include <nuttx/spi.h>
/************************************************************************************
@@ -113,8 +114,8 @@ extern "C" {
* for example, will bind the SPI driver to the SPI MMC/SD driver).
*/
-EXTERN void ez80_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected);
-EXTERN ubyte ez80_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+EXTERN void ez80_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
+EXTERN uint8_t ez80_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/arch/z80/src/ez80/switch.h b/nuttx/arch/z80/src/ez80/switch.h
index ef78d8420..b1d71669b 100644
--- a/nuttx/arch/z80/src/ez80/switch.h
+++ b/nuttx/arch/z80/src/ez80/switch.h
@@ -2,7 +2,7 @@
* arch/z80/src/ez80/switch.h
* arch/z80/src/chip/switch.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 @@
* Included Files
************************************************************************************/
-#include <sys/types.h>
#ifndef __ASSEMBLY__
# include <nuttx/sched.h>
# include <nuttx/arch.h>
@@ -62,7 +61,7 @@
#define INIT_IRQCONTEXT() current_regs = NULL
-/* IN_INTERRUPT returns TRUE if the system is current operating in the interrupt
+/* IN_INTERRUPT returns true if the system is current operating in the interrupt
* context. IN_INTERRUPT is the inline equivalent of up_interrupt_context().
*/
diff --git a/nuttx/arch/z80/src/ez80/up_mem.h b/nuttx/arch/z80/src/ez80/up_mem.h
index 6031d3985..724facbd3 100644
--- a/nuttx/arch/z80/src/ez80/up_mem.h
+++ b/nuttx/arch/z80/src/ez80/up_mem.h
@@ -2,7 +2,7 @@
* arch/z80/src/ez80/up_mem.h
* arch/z80/src/chip/up_mem.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,6 +41,8 @@
* Included Files
************************************************************************************/
+#include <stdint.h>
+
/************************************************************************************
* Definitions
************************************************************************************/
@@ -57,12 +59,12 @@
#ifndef CONFIG_HEAP1_BASE
extern unsigned long _heapbot;
-# define CONFIG_HEAP1_BASE ((uint24)&_heapbot)
+# define CONFIG_HEAP1_BASE ((uint24_t)&_heapbot)
#endif
#ifndef CONFIG_HEAP1_END
extern unsigned long _stack;
-# define CONFIG_HEAP1_END (((uint24)&_stack) - CONFIG_IDLETHREAD_STACKSIZE)
+# define CONFIG_HEAP1_END (((uint24_t)&_stack) - CONFIG_IDLETHREAD_STACKSIZE)
#endif
/************************************************************************************