You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@nuttx.apache.org by ag...@apache.org on 2020/03/09 21:52:03 UTC

[incubator-nuttx] branch master updated: z20x: Changes to reduce serial Rx data overrun

This is an automated email from the ASF dual-hosted git repository.

aguettouche pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/incubator-nuttx.git


The following commit(s) were added to refs/heads/master by this push:
     new 199b4d6  z20x:  Changes to reduce serial Rx data overrun
199b4d6 is described below

commit 199b4d68525b079eb0a38c9b938ec0dd99107fcc
Author: Gregory Nutt <gn...@nuttx.org>
AuthorDate: Mon Mar 9 14:28:20 2020 -0600

    z20x:  Changes to reduce serial Rx data overrun
    
    boards/z80/ez80/z20x:  Increase RX buffer size to 4Kb, reduce BAUD to 2400 in w25boot configuration
    arch/z80/src/ez80/ez80_serial.c:  Reduce Rx FIFO trigger level for eZ80F92 to 1 so that will respond more quickly to incoming data.
---
 arch/z80/src/ez80/Kconfig                      |  45 +++++++-
 arch/z80/src/ez80/ez80_serial.c                | 141 +++++++++++++------------
 arch/z80/src/ez80/ez80f91.h                    |  70 +++++-------
 arch/z80/src/ez80/ez80f92.h                    |   5 +-
 boards/z80/ez80/z20x/README.txt                |  69 ++++++------
 boards/z80/ez80/z20x/configs/w25boot/defconfig |   3 +-
 libs/libc/hex2bin/Make.defs                    |  39 +++----
 libs/libc/hex2bin/lib_fhex2mem.c               |  39 +++----
 libs/libc/hex2bin/lib_hex2bin.c                |  89 ++++++++--------
 libs/libc/hex2bin/lib_hex2mem.c                |  39 +++----
 libs/libc/stdio/lib_rawinstream.c              |  10 +-
 libs/libc/stdio/lib_rawsistream.c              |   6 +-
 12 files changed, 274 insertions(+), 281 deletions(-)

diff --git a/arch/z80/src/ez80/Kconfig b/arch/z80/src/ez80/Kconfig
index e3561b7..b22191b 100644
--- a/arch/z80/src/ez80/Kconfig
+++ b/arch/z80/src/ez80/Kconfig
@@ -5,6 +5,8 @@
 
 if ARCH_CHIP_EZ80
 
+# Chip capabilities
+
 config ARCH_EZ80_HAVE_PLL
 	bool
 	default n
@@ -21,6 +23,8 @@ config ARCH_EZ80_HAVE_TIMER_INTREGS
 	bool
 	default n
 
+# Chip selection
+
 choice
 	prompt "eZ80 Chip Selection"
 	default ARCH_CHIP_EZ80F91
@@ -72,6 +76,8 @@ config EZ80_ZDSII_V533
 
 endchoice # ZDS-II Toolchain version
 
+# Build type selection
+
 config EZ80_BOOTLOADER
 	bool
 	default n
@@ -89,20 +95,29 @@ config EZ80_PROGRAM
 		may require special properties such as re-direction of interrupts
 		(eZ80F92)
 
+# Peripheral selection
+
+config EZ80_UART
+	bool
+	default n
+
 menu "ez80 Peripheral Support"
 
 config EZ80_UART0
 	bool "UART0"
+	select EZ80_UART
 	select UART0_SERIALDRIVER
 	default n
 
 config EZ80_UART1
 	bool "UART1"
+	select EZ80_UART
 	select UART1_SERIALDRIVER
 	default n
 
 config EZ80_UART2
 	bool "UART2"
+	select EZ80_UART
 	select UART2_SERIALDRIVER
 	default n
 	depends on ARCH_EZ80_HAVE_UART2
@@ -132,6 +147,30 @@ config EZ80_EMAC
 
 endmenu # ez80 Peripheral Support
 
+# UART Configuration
+
+choice
+	prompt "UART Rx FIFO depth"
+	default EZ80_UART_RXFIFO_1 if ARCH_CHIP_EZ80F92 || ARCH_CHIP_EZ80F93
+	default EZ80_UART_RXFIFO_4 if ARCH_CHIP_EZ80F91
+	depends on EZ80_UART
+
+config EZ80_UART_RXFIFO_1
+	bool "1"
+
+config EZ80_UART_RXFIFO_4
+	bool "4"
+
+config EZ80_UART_RXFIFO_8
+	bool "8"
+
+config EZ80_UART_RXFIFO_14
+	bool "14"
+
+endchoice
+
+# RTC/Crystal Configuration
+
 config EZ80_RTC_32KHZ
 	bool "32KHz crystal present"
 	default y
@@ -148,10 +187,12 @@ config EZ80_RTC_LINEFREQ50
 		If there is no 32Hz crystal, the RTC will fall back to use the line
 		frequency, either 50 or 60Hz.
 
+# EMAC Configuration
+
 if EZ80_EMAC
 
 config EZ80_FIAD
-hex "PHY Address"
+	hex "PHY Address"
 	range 0x00 0x1f
 	default 0x1f
 	---help---
@@ -208,6 +249,8 @@ config ARCH_MCFILTER
 
 endif # EZ80_EMAC
 
+# System integration
+
 config ARCH_TIMERHOOK
 	bool "Timer Hook"
 	default n
diff --git a/arch/z80/src/ez80/ez80_serial.c b/arch/z80/src/ez80/ez80_serial.c
index bfa4e78..12ebaf5 100644
--- a/arch/z80/src/ez80/ez80_serial.c
+++ b/arch/z80/src/ez80/ez80_serial.c
@@ -1,36 +1,20 @@
 /****************************************************************************
  * arch/z80/src/ez08/ez80_serial.c
  *
- *   Copyright (C) 2008-2009, 2012, 2017 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
- *
- * 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.
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License. *
  ****************************************************************************/
 
 /****************************************************************************
@@ -67,12 +51,12 @@
 
 struct ez80_dev_s
 {
-  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) */
+  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) */
 };
 
 /****************************************************************************
@@ -285,7 +269,7 @@ static void ez80_disableuartint(FAR struct ez80_dev_s *priv)
 static void ez80_restoreuartint(FAR struct ez80_dev_s *priv, uint8_t bits)
 {
   uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
-  ier |= bits & (EZ80_UARTEIR_TIE|EZ80_UARTEIR_RIE);
+  ier |= bits & (EZ80_UARTEIR_TIE | EZ80_UARTEIR_RIE);
   ez80_serialout(priv, EZ80_UART_IER, ier);
 }
 
@@ -325,19 +309,19 @@ static void ez80_setbaud(FAR struct ez80_dev_s *priv, uint24_t baud)
    * BRG_Divisor = SYSTEM_CLOCK_FREQUENCY / 16 / BAUD
    */
 
-   brg_divisor = (ez80_systemclock + (baud << 3)) / (baud << 4);
+  brg_divisor = (ez80_systemclock + (baud << 3)) / (baud << 4);
 
-   /* Set the DLAB bit to enable access to the BRG registers */
+  /* Set the DLAB bit to enable access to the BRG registers */
 
-   lctl = ez80_serialin(priv, EZ80_UART_LCTL);
-   lctl |= EZ80_UARTLCTL_DLAB;
-   ez80_serialout(priv, EZ80_UART_LCTL, lctl);
+  lctl = ez80_serialin(priv, EZ80_UART_LCTL);
+  lctl |= EZ80_UARTLCTL_DLAB;
+  ez80_serialout(priv, EZ80_UART_LCTL, lctl);
 
-   ez80_serialout(priv, EZ80_UART_BRGL, (uint8_t)(brg_divisor & 0xff));
-   ez80_serialout(priv, EZ80_UART_BRGH, (uint8_t)(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);
+  lctl &= ~EZ80_UARTLCTL_DLAB;
+  ez80_serialout(priv, EZ80_UART_LCTL, lctl);
 }
 
 /****************************************************************************
@@ -376,7 +360,7 @@ static int ez80_setup(FAR struct uart_dev_s *dev)
     }
   else if (priv->parity == 2)  /* Even parity */
     {
-      cval |= (EZ80_UARTLCTL_PEN|EZ80_UARTLCTL_EPS);
+      cval |= (EZ80_UARTLCTL_PEN | EZ80_UARTLCTL_EPS);
     }
 
   /* Set the baud rate */
@@ -392,16 +376,32 @@ static int ez80_setup(FAR struct uart_dev_s *dev)
 
   /* Enable and flush the receive FIFO */
 
-  reg = EZ80_UARTFCTL_FIFOEN;
+  reg  = EZ80_UARTFCTL_FIFOEN;
   ez80_serialout(priv, EZ80_UART_FCTL, reg);
-  reg |= (EZ80_UARTFCTL_CLRTxF|EZ80_UARTFCTL_CLRRxF);
+  reg |= (EZ80_UARTFCTL_CLRTXF | EZ80_UARTFCTL_CLRRXF);
   ez80_serialout(priv, EZ80_UART_FCTL, reg);
 
-  /* Set the receive trigger level to 4 */
+  /* Set the Rx FIFO trigger level.  Small values assure the quickest
+   * response to get data from the Rx FIFO.  This minimizes the
+   * likelihood of Rx overruns with a penalty of more time spent
+   * handling Rx interrupts.
+   */
 
+#if defined(CONFIG_EZ80_UART_RXFIFO_1)
+  reg |= EZ80_UARTTRIG_1;
+#elif defined(CONFIG_EZ80_UART_RXFIFO_4)
   reg |= EZ80_UARTTRIG_4;
+#elif defined(CONFIG_EZ80_UART_RXFIFO_8)
+  reg |= EZ80_UARTTRIG_8;
+#elif defined(CONFIG_EZ80_UART_RXFIFO_14)
+  reg |= EZ80_UARTTRIG_14;
+#else
+#  error No Rx FIFO trigger level
+#endif
+
   ez80_serialout(priv, EZ80_UART_FCTL, reg);
 #endif
+
   return OK;
 }
 
@@ -415,7 +415,7 @@ static int ez80_setup(FAR struct uart_dev_s *dev)
 
 static void ez80_shutdown(FAR struct uart_dev_s *dev)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   ez80_disableuartint(priv);
 }
 
@@ -423,20 +423,21 @@ static void ez80_shutdown(FAR struct uart_dev_s *dev)
  * Name: ez80_attach
  *
  * Description:
- *   Configure the UART to operation in interrupt driven mode.  This method is
- *   called when the serial port is opened.  Normally, this is just after the
- *   the setup() method is called, however, the serial console may operate in
- *   a non-interrupt driven mode during the boot phase.
+ *   Configure the UART to operation in interrupt driven mode.  This method
+ *   is called when the serial port is opened.  Normally, this is just after
+ *   the the setup() method is called, however, the serial console may
+ *   operate in a non-interrupt driven mode during the boot phase.
  *
- *   RX and TX interrupts are not enabled when by the attach method (unless the
- *   hardware supports multiple levels of interrupt enabling).  The RX and TX
- *   interrupts are not enabled until the txint() and rxint() methods are called.
+ *   RX and TX interrupts are not enabled when by the attach method (unless
+ *   the hardware supports multiple levels of interrupt enabling).  The RX
+ *   and TX interrupts are not enabled until the txint() and rxint() methods
+ *   are called.
  *
  ****************************************************************************/
 
 static int ez80_attach(FAR struct uart_dev_s *dev)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
 
   /* Attach the IRQ */
 
@@ -448,14 +449,14 @@ static int ez80_attach(FAR 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.
  *
  ****************************************************************************/
 
 static void ez80_detach(FAR struct uart_dev_s *dev)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   ez80_disableuartint(priv);
   irq_detach(priv->irq);
 }
@@ -480,7 +481,7 @@ static int ez80_interrupt(int irq, FAR void *context, FAR void *arg)
   volatile uint32_t  cause;
 
   DEBUGASSERT(dev != NULL && dev->priv != NULL);
-  priv = (struct ez80_dev_s*)dev->priv;
+  priv = (struct ez80_dev_s *)dev->priv;
 
   cause = ez80_serialin(priv, EZ80_UART_IIR) & EZ80_UARTIIR_CAUSEMASK;
 
@@ -528,7 +529,7 @@ static int ez80_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
 
 static int ez80_receive(FAR struct uart_dev_s *dev, FAR unsigned int *status)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   uint8_t rbr = ez80_serialin(priv, EZ80_UART_RBR);
   uint8_t lsr = ez80_serialin(priv, EZ80_UART_LSR);
 
@@ -546,7 +547,7 @@ static int ez80_receive(FAR struct uart_dev_s *dev, FAR unsigned int *status)
 
 static void ez80_rxint(FAR struct uart_dev_s *dev, bool enable)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
 
   if (enable)
@@ -573,7 +574,7 @@ static void ez80_rxint(FAR struct uart_dev_s *dev, bool enable)
 
 static bool ez80_rxavailable(FAR struct uart_dev_s *dev)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   return (ez80_serialin(priv, EZ80_UART_LSR) & EZ80_UARTLSR_DR) != 0;
 }
 
@@ -587,7 +588,7 @@ static bool ez80_rxavailable(FAR struct uart_dev_s *dev)
 
 static void ez80_send(FAR struct uart_dev_s *dev, int ch)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   ez80_serialout(priv, EZ80_UART_THR, (uint8_t)ch);
 }
 
@@ -601,7 +602,7 @@ static void ez80_send(FAR struct uart_dev_s *dev, int ch)
 
 static void ez80_txint(FAR struct uart_dev_s *dev, bool enable)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
 
   if (enable)
@@ -628,7 +629,7 @@ static void ez80_txint(FAR struct uart_dev_s *dev, bool enable)
 
 static bool ez80_txready(FAR struct uart_dev_s *dev)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   return (ez80_serialin(priv, EZ80_UART_LSR) & EZ80_UARTLSR_THRE) != 0;
 }
 
@@ -642,7 +643,7 @@ static bool ez80_txready(FAR struct uart_dev_s *dev)
 
 static bool ez80_txempty(FAR struct uart_dev_s *dev)
 {
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)dev->priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)dev->priv;
   return (ez80_serialin(priv, EZ80_UART_LSR) & EZ80_UARTLSR_TEMT) != 0;
 }
 
@@ -733,7 +734,7 @@ void z80_serial_initialize(void)
 int up_putc(int ch)
 {
 #ifdef CONSOLE_DEV
-  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s*)CONSOLE_DEV.priv;
+  FAR struct ez80_dev_s *priv = (FAR struct ez80_dev_s *)CONSOLE_DEV.priv;
   uint8_t ier = ez80_serialin(priv, EZ80_UART_IER);
 
   ez80_disableuartint(priv);
diff --git a/arch/z80/src/ez80/ez80f91.h b/arch/z80/src/ez80/ez80f91.h
index f4d6153..ed6ed36 100644
--- a/arch/z80/src/ez80/ez80f91.h
+++ b/arch/z80/src/ez80/ez80f91.h
@@ -1,36 +1,20 @@
 /************************************************************************************
  * arch/z80/src/ez80/ez80f91.h
  *
- *   Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * 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.
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License. *
  ************************************************************************************/
 
 #ifndef __ARCH_Z80_SRC_EZ80_EZ80F91_H
@@ -195,7 +179,7 @@
 #define EZ80_TMR3_OC3L         0x88        /* RW: Timer 3 output compare value 3 (low) */
 #define EZ80_TMR3_OC3H         0x89        /* RW: Timer 3 output compare value 3 (high) */
 
-/* TMR0/1/2/3 CTL Register Bit Definitions *******************************************/
+/* TMR0/1/2/3 CTL Register Bit Definitions ******************************************/
 
 #define EZ80_TMRCTL_BRKSTOP    0x80        /* Bit 7: Stop timer for debug operation */
 #define EZ80_TMRCTL_CLKSEL     0x60        /* Bits 6-5: Timer source */
@@ -212,7 +196,8 @@
 #define EZ80_TMRCTL_RLD        0x02        /* Bit 1: Force reload */
 #define EZ80_TMRCTL_TIMEN      0x01        /* Bit 0: Programmable reload timer enabled */
 
-/* TMR0/1/2/3 IER Register Bit Definitions *******************************************/
+/* TMR0/1/2/3 IER Register Bit Definitions ******************************************/
+
                                            /* Bit 7: Reserved */
 #define EZ80_TMRIER_OC3EN      0x40        /* Bit 6: TMR3 OC3 enabled */
 #define EZ80_TMRIER_OC2EN      0x20        /* Bit 5: TMR3 OC2 enabled */
@@ -222,7 +207,8 @@
 #define EZ80_TMRIER_ICAEN      0x02        /* Bit 1: TMR1/3 capture pin enabled */
 #define EZ80_TMRIER_EOCEN      0x01        /* Bit 0: End of count interrupt enabled */
 
-/* TMR0/1/2/3 IER Register Bit Definitions *******************************************/
+/* TMR0/1/2/3 IER Register Bit Definitions ******************************************/
+
                                            /* Bit 7: Reserved */
 #define EZ80_TMRIIR_OC3        0x40        /* Bit 6: TMR3 OC3 */
 #define EZ80_TMRIIR_OC2        0x20        /* Bit 5: TMR3 OC2 */
@@ -232,7 +218,7 @@
 #define EZ80_TMRIIR_ICA        0x02        /* Bit 1: TMR1/3 capture pin */
 #define EZ80_TMRIIR_EOC        0x01        /* Bit 0: End of count interrupt */
 
-/* PWM Registers *********************************************************************/
+/* PWM Registers ********************************************************************/
 
 #define EZ80_PWM_CTL1          0x79
 #define EZ80_PWM_CTL2          0x7a
@@ -254,12 +240,12 @@
 #define EZ80_PWM3F_L           0x8a
 #define EZ80_PWM3F_H           0x8b
 
-/* WDT Registers *********************************************************************/
+/* WDT Registers ********************************************************************/
 
 #define EZ80_WDT_CTL           0x93
 #define EZ80_WDT_RR            0x94
 
-/* GPIO Registers ********************************************************************/
+/* GPIO Registers *******************************************************************/
 
 #define EZ80_PA_DR             0x96
 #define EZ80_PA_DDR            0x97
@@ -282,7 +268,7 @@
 #define EZ80_PD_ALT1           0xa4
 #define EZ80_PD_ALT2           0xa5
 
-/* CS Registers **********************************************************************/
+/* CS Registers *********************************************************************/
 
 #define EZ80_CS0_LBR           0xa8
 #define EZ80_CS0_UBR           0xa9
@@ -297,7 +283,7 @@
 #define EZ80_CS3_UBR           0xb2
 #define EZ80_CS3_CTL           0xb3
 
-/* RAMCTL reggisters *****************************************************************/
+/* RAMCTL reggisters ****************************************************************/
 
 #define EZ80_RAM_CTL           0xb4
 #define EZ80_RAM_CTL0          0xb4
@@ -305,12 +291,12 @@
 #define EZ80_MBIST_GPR         0xb6
 #define EZ80_MBIST_EMR         0xb7
 
-/* RAMCTL bit definitions ************************************************************/
+/* RAMCTL bit definitions ***********************************************************/
 
 #define RAMCTL_ERAMEN          (1 << 6) /* Bit 7: 1=On chip EMAC SRAM is enabled */
 #define RAMCTL_GPRAMEN         (1 << 7) /* Bit 7: 1=On chip GP SRAM is enabled */
 
-/* SPI Registers *********************************************************************/
+/* SPI Registers ********************************************************************/
 
 #define EZ80_SPI_BRG_L         0xb8
 #define EZ80_SPI_BRG_H         0xb9
@@ -319,7 +305,8 @@
 #define EZ80_SPI_RBR           0xbc
 #define EZ80_SPI_TSR           0xbc
 
-/* UART Register Offsets *************************************************************/
+/* UART Register Offsets ************************************************************/
+
                                            /* DLAB=0: */
 #define EZ80_UART_THR          0x00        /*    W: UART Transmit holding register */
 #define EZ80_UART_RBR          0x00        /*   R : UART Receive buffer register */
@@ -373,8 +360,8 @@
 #  define EZ80_UARTTRIG_8      0x80         /*   10: Receive FIFO trigger level=8 */
 #  define EZ80_UARTTRIG_14     0xc0         /*   11: Receive FIFO trigger level=14 */
                                             /* Bit 3-5: Reserved */
-#define EZ80_UARTFCTL_CLRTxF   0x04         /* Bit 2: Transmit enable */
-#define EZ80_UARTFCTL_CLRRxF   0x02         /* Bit 1: Receive enable */
+#define EZ80_UARTFCTL_CLRTXF   0x04         /* Bit 2: Transmit enable */
+#define EZ80_UARTFCTL_CLRRXF   0x02         /* Bit 1: Receive enable */
 #define EZ80_UARTFCTL_FIFOEN   0x01         /* Bit 0: Enable receive/transmit FIFOs */
 
 /* UART0/1 LCTL register bits *******************************************************/
@@ -394,6 +381,7 @@
 #define EZ80_UARTLCTL_MASK     0x3f
 
 /* UART0/1 MCTL register bits *******************************************************/
+
                                             /* Bit 7: Reserved */
 #define EZ80_UARTMCTL_POLARITY 0x40         /* Bit 6: Invert polarity of RxD and TxD */
 #define EZ80_UARTMCTL_MDM      0x20         /* Bit 5: Multi-drop mode enable */
diff --git a/arch/z80/src/ez80/ez80f92.h b/arch/z80/src/ez80/ez80f92.h
index f338f2a..d64b8e0 100644
--- a/arch/z80/src/ez80/ez80f92.h
+++ b/arch/z80/src/ez80/ez80f92.h
@@ -166,6 +166,7 @@
 #define EZ80_IR_CTL            0xbf        /* Infrared Encoder/Decoder Control */
 
 /* UART Register Offsets ************************************************************/
+
                                            /* DLAB=0: */
 #define EZ80_UART_THR          0x00        /*    W: UART Transmit holding register */
 #define EZ80_UART_RBR          0x00        /*   R : UART Receive buffer register */
@@ -222,8 +223,8 @@
 #  define EZ80_UARTTRIG_8      0x80         /*   10: Receive FIFO trigger level=8 */
 #  define EZ80_UARTTRIG_14     0xc0         /*   11: Receive FIFO trigger level=14 */
                                             /* Bit 3-5: Reserved */
-#define EZ80_UARTFCTL_CLRTxF   0x04         /* Bit 2: Transmit enable */
-#define EZ80_UARTFCTL_CLRRxF   0x02         /* Bit 1: Receive enable */
+#define EZ80_UARTFCTL_CLRTXF   0x04         /* Bit 2: Transmit enable */
+#define EZ80_UARTFCTL_CLRRXF   0x02         /* Bit 1: Receive enable */
 #define EZ80_UARTFCTL_FIFOEN   0x01         /* Bit 0: Enable receive/transmit FIFOs */
 
 /* UART0/1 LCTL register bits *******************************************************/
diff --git a/boards/z80/ez80/z20x/README.txt b/boards/z80/ez80/z20x/README.txt
index 60f0046..bab4a57 100644
--- a/boards/z80/ez80/z20x/README.txt
+++ b/boards/z80/ez80/z20x/README.txt
@@ -306,44 +306,43 @@ Configuration Subdirectories
        - The stack sizes have not been tuned and, hence, are probably too
          large.
 
-  sdboot
+  w25boot
 
     This configuration implements a very simple boot loader.  In runs from
-    FLASH and simply initializes the external SRAM, mounts the FAT file
-    system on the SD card, and checks to see if there is a file called
-    nuttx.hex on the SD card.  If so, it will load the Intel HEX file into
-    memory and jump to address 0x040000.  This, of course, assumes that
-    the application's reset vector resides at address 0x040000 in external
-    SRAM.
+    FLASH and simply initializes the external SRAM, mounts the W25 FLASH
+    and checks to see if there is a valid binary image at the beginning of
+    FLASH.  If so, it will load the binary into RAM, verify it and jump to
+    0x50000.  This, of course, assumes that the application's entry point
+    vector resides at address 0x050000 in external SRAM.
 
-    The boot loader source is located at boards/z20x/src/sd_main.c.
+    The boot loader source is located at boards/z20x/src/w25_main.c.
 
     NOTES:
 
-    1. This version of the eZ80 bootloader is not usable in its current
-       state.  That is because the the eZ80F92 Interrupt Controller is
-       not as robust as the eZ80F91 Interrupt Controller.  A consequence
-       is that the interrupt vectors must always reside within the first
-       64Kb of FLASH memory.  It will not be possible to run programs in
-       SRAM *unless* some mechanism is developed to redirect interrupts
-       from ROM and into loaded SRAM logic.
-
-       For example, it might be possible to implement this kind of
-       vectoring to get to a RAM based interrupt handler:
-
-       a. The initial 16-bit address in the interrupt vector table can
-          transfer the interrupt to a larger jump table also in lower
-          flash memory.
-       b. That jump table could vector to another jump table at a known
-          location RAM.
-       c. The RAM jump table could then jump to the final RAM-based
-          interrupt handler.
-
-       This would effect the logic in arch/z80/src/ez80/ez80f92_handlers.am
-       and possible the z20x *.linkcmd files.
-
-    2. Another thing that would have to be done before this configuration
-       would be usable is to partition the external in some way so that
-       there is no collision between the bootloader's use of SRAM and the
-       SRAM required by the newly loaded program.
-
+    1. A large UART1 Rx buffer (4Kb), a slow UART1 BAUD (2400), and a very
+       low Rx FIFO trigger are used to avoid serial data overruns.  Running
+       at only 20MHz, the eZ80F92 is unable to process 115200 BAUD Intel Hex
+       at speed.  It is likely that a usable BAUD higher than 2400 could be
+       found through experimentation; it could also be possible to implement
+       some software handshake to protect the eZ80f92 from overrun (the
+       eZ80F92 does not support hardware flow control)
+
+       At 2400 BAUD the download takes a considerable amount of time but
+       seems to be reliable
+
+       Massive data loss occurs due to overruns at 115200 BAUD.  I have
+       tried the bootloader at 9600 with maybe 30-40% data loss, too much
+       data loss to be usable.  At 9600 baud, the Rx data overrun appears
+       to be in the Rx FIFO; the data loss symptom is small sequences of
+       around 8-10 bytes often missing in the data.  Apparently, the Rx FIFO
+       overflows before the poor little  eZ80F92 can service the Rx
+       interrupt and clear the FIFO.
+
+       The Rx FIFO trigger is set at 1 so that the ez80F92 will respond as
+       quickly to receipt of Rx data is possible and clear out the Rx FIFO.
+       The Rx FIFO trigger level is a trade-off be fast responsiveness and
+       reduced chance of Rx FIFO overrun (low) versus reduced Rx interrupt
+       overhead (high).
+
+       Things worth trying:  4800 BAUD, smaller Rx buffer, large Rx FIFO
+       trigger level.
diff --git a/boards/z80/ez80/z20x/configs/w25boot/defconfig b/boards/z80/ez80/z20x/configs/w25boot/defconfig
index 80b4f03..3059947 100644
--- a/boards/z80/ez80/z20x/configs/w25boot/defconfig
+++ b/boards/z80/ez80/z20x/configs/w25boot/defconfig
@@ -32,8 +32,9 @@ CONFIG_RAM_SIZE=65536
 CONFIG_SDCLONE_DISABLE=y
 CONFIG_START_MONTH=3
 CONFIG_START_YEAR=2020
+CONFIG_UART1_BAUD=2400
 CONFIG_UART1_BITS=0
-CONFIG_UART1_RXBUFSIZE=64
+CONFIG_UART1_RXBUFSIZE=4096
 CONFIG_UART1_SERIAL_CONSOLE=y
 CONFIG_UART1_TXBUFSIZE=64
 CONFIG_USER_ENTRYPOINT="w25_main"
diff --git a/libs/libc/hex2bin/Make.defs b/libs/libc/hex2bin/Make.defs
index 87be8d9..b6a2747 100644
--- a/libs/libc/hex2bin/Make.defs
+++ b/libs/libc/hex2bin/Make.defs
@@ -1,35 +1,20 @@
 ############################################################################
 # libs/libc/hex2bin/Make.defs
 #
-#   Copyright (C) 2016 Gregory Nutt. All rights reserved.
-#   Author: Gregory Nutt <gn...@nuttx.org>
+# Licensed to the Apache Software Foundation (ASF) under one or more
+# contributor license agreements.  See the NOTICE file distributed with
+# this work for additional information regarding copyright ownership.  The
+# ASF licenses this file to you under the Apache License, Version 2.0 (the
+# "License"); you may not use this file except in compliance with the
+# License.  You may obtain a copy of the License at
 #
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
+#   http://www.apache.org/licenses/LICENSE-2.0
 #
-# 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.
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+# License for the specific language governing permissions and limitations
+# under the License.
 #
 ############################################################################
 
diff --git a/libs/libc/hex2bin/lib_fhex2mem.c b/libs/libc/hex2bin/lib_fhex2mem.c
index c22b0fb..f3ff3ce 100644
--- a/libs/libc/hex2bin/lib_fhex2mem.c
+++ b/libs/libc/hex2bin/lib_fhex2mem.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * libs/libc/hex2bin/fhex2mem.c
  *
- *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
diff --git a/libs/libc/hex2bin/lib_hex2bin.c b/libs/libc/hex2bin/lib_hex2bin.c
index f64b3bc..5d2f7c6 100644
--- a/libs/libc/hex2bin/lib_hex2bin.c
+++ b/libs/libc/hex2bin/lib_hex2bin.c
@@ -1,41 +1,29 @@
 /****************************************************************************
  * libs/libc/hex2bin/hex2bin.c
  *
- *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
  * References:
  *   - http://en.wikipedia.org/wiki/Intel_HEX
  *   - Hexadecimal Object File Format Specification, Revision A January 6,
  *     1988, Intel
  *
- * 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.
- *
  ****************************************************************************/
 
 /****************************************************************************
@@ -208,7 +196,7 @@ static int word2bin(FAR const char *ascii)
  * Name: data2bin
  ****************************************************************************/
 
-int data2bin(FAR uint8_t* dest, FAR const uint8_t *src, int nsrcbytes)
+int data2bin(FAR uint8_t *dest, FAR const uint8_t *src, int nsrcbytes)
 {
   int byte;
 
@@ -220,7 +208,8 @@ int data2bin(FAR uint8_t* dest, FAR const uint8_t *src, int nsrcbytes)
     }
 
   /* Convert src bytes in groups of 2, writing one byte to the output on each
-   * pass through the loop. */
+   * pass through the loop.
+   */
 
   while (nsrcbytes > 0)
     {
@@ -270,7 +259,7 @@ static int readstream(FAR struct lib_instream_s *instream,
 
   /* Then read, verify, and buffer until the end of line is encountered */
 
-  while (ch != EOF && nbytes < (MAXRECORD_ASCSIZE-1))
+  while (ch != EOF && nbytes < (MAXRECORD_ASCSIZE - 1))
     {
 #if defined(CONFIG_EOL_IS_LF)
       if (ch == '\n')
@@ -289,12 +278,14 @@ static int readstream(FAR struct lib_instream_s *instream,
           *line = '\0';
           return nbytes;
         }
+
 #elif defined(CONFIG_EOL_IS_CR)
       if (ch == '\r')
         {
           *line = '\0';
           return nbytes;
         }
+
 #elif defined(CONFIG_EOL_IS_EITHER_CRLF)
       if (ch == '\n' || ch == '\r')
         {
@@ -302,6 +293,7 @@ static int readstream(FAR struct lib_instream_s *instream,
           return nbytes;
         }
 #endif
+
       /* Only hex data goes into the line buffer */
 
       else if (isxdigit(ch))
@@ -387,8 +379,8 @@ static inline void writedata(FAR struct lib_sostream_s *outstream,
  *   the binary to the seek-able serial OUT stream.
  *
  *   These streams may be files or, in another usage example, the IN stream
- *   could be a serial port and the OUT stream could be a memory stream.  This
- *   would decode and write the serial input to memory.
+ *   could be a serial port and the OUT stream could be a memory stream.
+ *   This would decode and write the serial input to memory.
  *
  * Input Parameters:
  *   instream  - The incoming stream from which Intel HEX data will be
@@ -444,6 +436,10 @@ int hex2bin(FAR struct lib_instream_s *instream,
   expected = 0;
   lineno = 0;
 
+  /* Read and process the HEX input stream stream until the end of file
+   * record is received (or until an error occurs)
+   */
+
   while ((nbytes = readstream(instream, line, lineno)) != EOF)
     {
       /* Increment the line number */
@@ -518,7 +514,7 @@ int hex2bin(FAR struct lib_instream_s *instream,
       /* Get the 16-bit (unextended) address from the record */
 
       address16 = (uint16_t)bin[ADDRESS_BINNDX] << 8 |
-                  (uint16_t)bin[ADDRESS_BINNDX+1];
+                  (uint16_t)bin[ADDRESS_BINNDX + 1];
 
       /* Handle the record by its record type */
 
@@ -537,7 +533,8 @@ int hex2bin(FAR struct lib_instream_s *instream,
                 {
                   if ((bytecount & 1) != 0)
                     {
-                      lerr("Line %d ERROR: Byte count %d is not a multiple of 2\n",
+                      lerr("Line %d ERROR: Byte count %d is not a multiple "
+                           "of 2\n",
                            lineno, bytecount);
                        goto errout_with_einval;
                     }
@@ -552,7 +549,8 @@ int hex2bin(FAR struct lib_instream_s *instream,
                 {
                   if ((bytecount & 3) != 0)
                     {
-                      lerr("Line %d ERROR: Byte count %d is not a multiple of 4\n",
+                      lerr("Line %d ERROR: Byte count %d is not a multiple "
+                           "of 4\n",
                            lineno, bytecount);
                        goto errout_with_einval;
                     }
@@ -577,7 +575,8 @@ int hex2bin(FAR struct lib_instream_s *instream,
 
             if (address < baseaddr || (endpaddr != 0 && endaddr >= endpaddr))
               {
-                lerr("Line %d ERROR: Extended address %08lx is out of range\n",
+                lerr("Line %d ERROR: Extended address %08lx is out of "
+                     "range\n",
                      lineno, (unsigned long)address);
                 goto errout_with_einval;
               }
@@ -588,7 +587,8 @@ int hex2bin(FAR struct lib_instream_s *instream,
 
             if (address != expected)
               {
-                off_t pos = outstream->seek(outstream, address - baseaddr, SEEK_SET);
+                off_t pos = outstream->seek(outstream,
+                                            address - baseaddr, SEEK_SET);
                 if (pos == (off_t)-1)
                   {
                     lerr("Line %u ERROR: Seek to address %08lu failed\n",
@@ -609,6 +609,7 @@ int hex2bin(FAR struct lib_instream_s *instream,
           break;
 
         case RECORD_EOF: /* End of file */
+
           /*  End Of File record.  Must occur exactly once per file in the
            * last line of the file. The byte count is 00 and the data field
            * is empty. Usually the address field is also 0000.
@@ -625,6 +626,7 @@ int hex2bin(FAR struct lib_instream_s *instream,
           goto errout_with_einval;
 
         case RECORD_EXT_SEGADDR: /* Extended segment address record */
+
           /* The address specified by the data field is multiplied by 16
            * (shifted 4 bits left) and added to the subsequent data record
            * addresses. This allows addressing of up to a megabyte of
@@ -634,12 +636,12 @@ int hex2bin(FAR struct lib_instream_s *instream,
            * 0.
            */
 
-          if (bytecount != 2 || address16 != 0 || bin[DATA_BINNDX+1] != 0)
+          if (bytecount != 2 || address16 != 0 || bin[DATA_BINNDX + 1] != 0)
             {
               lerr("Line %u ERROR: Invalid segment address\n", lineno);
               lerr("  bytecount=%d address=%04x segment=%02x%02x\n",
                    bytecount, address16, bin[DATA_BINNDX],
-                   bin[DATA_BINNDX+1]);
+                   bin[DATA_BINNDX + 1]);
               goto errout_with_einval;
             }
 
@@ -647,6 +649,7 @@ int hex2bin(FAR struct lib_instream_s *instream,
           break;
 
         case RECORD_START_SEGADDR: /* Start segment address record */
+
           /* For 80x86 processors, it specifies the initial content of
            * the CS:IP registers. The address field is 0000, the byte
            * count is 04, the first two bytes are the CS value, the
@@ -656,6 +659,7 @@ int hex2bin(FAR struct lib_instream_s *instream,
           break;
 
         case RECORD_EXT_LINADDR: /* Extended linear address record */
+
           /* The address field is 0000, the byte count is 02. The two
            * data bytes (two hex digit pairs in big endian order)
            * represent the upper 16 bits of the 32 bit address for
@@ -675,10 +679,11 @@ int hex2bin(FAR struct lib_instream_s *instream,
             }
 
           extension = (uint16_t)bin[DATA_BINNDX] << 8 |
-                      (uint16_t)bin[DATA_BINNDX+1];
+                      (uint16_t)bin[DATA_BINNDX + 1];
           break;
 
         case RECORD_START_LINADDR: /* Start linear address record */
+
           /* The address field is 0000, the byte count is 04. The 4
            * data bytes represent the 32-bit value loaded into the EIP
            * register of the 80386 and higher CPU.
diff --git a/libs/libc/hex2bin/lib_hex2mem.c b/libs/libc/hex2bin/lib_hex2mem.c
index b2b8767..40b632e 100644
--- a/libs/libc/hex2bin/lib_hex2mem.c
+++ b/libs/libc/hex2bin/lib_hex2mem.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * libs/libc/hex2bin/hex2mem.c
  *
- *   Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
- *   Author: Gregory Nutt <gn...@nuttx.org>
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
  *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
+ *   http://www.apache.org/licenses/LICENSE-2.0
  *
- * 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.
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
  *
  ****************************************************************************/
 
diff --git a/libs/libc/stdio/lib_rawinstream.c b/libs/libc/stdio/lib_rawinstream.c
index eae681f..f24edff 100644
--- a/libs/libc/stdio/lib_rawinstream.c
+++ b/libs/libc/stdio/lib_rawinstream.c
@@ -43,15 +43,15 @@
 static int rawinstream_getc(FAR struct lib_instream_s *this)
 {
   FAR struct lib_rawinstream_s *rthis = (FAR struct lib_rawinstream_s *)this;
-  int nwritten;
+  int nread;
   char ch;
 
   DEBUGASSERT(this && rthis->fd >= 0);
 
   /* Attempt to read one character */
 
-  nwritten = _NX_READ(rthis->fd, &ch, 1);
-  if (nwritten == 1)
+  nread = _NX_READ(rthis->fd, &ch, 1);
+  if (nread == 1)
     {
       this->nget++;
       return ch;
@@ -59,8 +59,8 @@ static int rawinstream_getc(FAR struct lib_instream_s *this)
 
   /* Return EOF on any failure to read from the incoming byte stream. The
    * only expected error is EINTR meaning that the read was interrupted
-   * by a signal.  A Zero return value would indicated an end-of-file
-   * confition.
+   * by a signal.  A Zero return value would indicate an end-of-file
+   * condition.
    */
 
   return EOF;
diff --git a/libs/libc/stdio/lib_rawsistream.c b/libs/libc/stdio/lib_rawsistream.c
index 84f5130..9a51fb8 100644
--- a/libs/libc/stdio/lib_rawsistream.c
+++ b/libs/libc/stdio/lib_rawsistream.c
@@ -43,15 +43,15 @@
 static int rawsistream_getc(FAR struct lib_sistream_s *this)
 {
   FAR struct lib_rawsistream_s *rthis = (FAR struct lib_rawsistream_s *)this;
-  int nwritten;
+  int nread;
   char ch;
 
   DEBUGASSERT(this && rthis->fd >= 0);
 
   /* Attempt to read one character */
 
-  nwritten = _NX_READ(rthis->fd, &ch, 1);
-  if (nwritten == 1)
+  nread = _NX_READ(rthis->fd, &ch, 1);
+  if (nread == 1)
     {
       this->nget++;
       return ch;