You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@nuttx.apache.org by ac...@apache.org on 2020/05/17 17:01:10 UTC

[incubator-nuttx] 02/02: Run nxstyle all .c and .h files modified by PR.

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

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

commit 57bc329aace6d816b9a51a368665ea4c7116a9c6
Author: Gregory Nutt <gn...@nuttx.org>
AuthorDate: Sun May 17 08:47:40 2020 -0600

    Run nxstyle all .c and .h files modified by PR.
---
 drivers/1wire/1wire.c                             |   4 +-
 drivers/analog/adc.c                              |   6 +-
 drivers/analog/comp.c                             |   4 +-
 drivers/analog/dac.c                              |   8 +-
 drivers/can/can.c                                 |   4 +-
 drivers/input/ads7843e.c                          |   4 +-
 drivers/input/max11802.c                          |   8 +-
 drivers/input/tsc2007.c                           | 271 ++++++++++----------
 drivers/net/rpmsgdrv.c                            |  51 ++--
 drivers/net/tun.c                                 |   4 +-
 drivers/pipes/pipe_common.c                       |  40 ++-
 drivers/sensors/lis3dh.c                          |  14 +-
 drivers/serial/pty.c                              |   3 +-
 drivers/syslog/ramlog.c                           |  73 +++---
 drivers/timers/pwm.c                              |  12 +-
 drivers/timers/rpmsg_rtc.c                        |  29 ++-
 drivers/usbhost/usbhost_xboxcontroller.c          |  32 ++-
 drivers/video/video.c                             |  44 ++--
 drivers/wireless/bluetooth/bt_uart_bcm4343x.c     |   4 +-
 drivers/wireless/bluetooth/bt_uart_shim.c         |  21 +-
 drivers/wireless/ieee80211/bcm43xxx/bcmf_driver.c |  98 +++++---
 drivers/wireless/ieee80211/bcm43xxx/bcmf_sdio.c   |  21 +-
 drivers/wireless/ieee802154/xbee/xbee.c           | 286 +++++++++++++---------
 drivers/wireless/ieee802154/xbee/xbee_netdev.c    | 121 +++++----
 fs/hostfs/hostfs_rpmsg.c                          |   8 +-
 graphics/nxterm/nxterm_register.c                 |  42 ++--
 include/nuttx/mutex.h                             |   7 +-
 net/arp/arp_send.c                                |  43 ++--
 net/bluetooth/bluetooth_recvfrom.c                |  53 ++--
 net/bluetooth/bluetooth_sendto.c                  |  49 ++--
 net/icmp/icmp_recvfrom.c                          |  59 ++---
 net/icmp/icmp_sendto.c                            |  78 +++---
 net/icmpv6/icmpv6_autoconfig.c                    |  80 +++---
 net/icmpv6/icmpv6_neighbor.c                      |  56 ++---
 net/icmpv6/icmpv6_recvfrom.c                      |  59 ++---
 net/icmpv6/icmpv6_sendto.c                        |  72 +++---
 net/ieee802154/ieee802154_recvfrom.c              |  65 ++---
 net/ieee802154/ieee802154_sendto.c                |  51 ++--
 net/local/local_connect.c                         |  47 ++--
 net/tcp/tcp_connect.c                             |  46 ++--
 net/tcp/tcp_recvfrom.c                            |  77 +++---
 net/tcp/tcp_sendfile.c                            |  16 +-
 net/udp/udp_sendto_unbuffered.c                   |  48 ++--
 net/usrsock/usrsock_conn.c                        |  13 +-
 sched/pthread/pthread_condsignal.c                |  54 ++--
 sched/pthread/pthread_mutexinit.c                 |  42 ++--
 46 files changed, 1097 insertions(+), 1130 deletions(-)

diff --git a/drivers/1wire/1wire.c b/drivers/1wire/1wire.c
index 52c4fb4..eb3cad2 100644
--- a/drivers/1wire/1wire.c
+++ b/drivers/1wire/1wire.c
@@ -201,7 +201,9 @@ static int onewire_pm_prepare(FAR struct pm_callback_s *cb, int domain,
 
       if (sval <= 0)
         {
-          /* Exclusive lock is held, do not allow entry to deeper PM states. */
+          /* Exclusive lock is held, do not allow entry to deeper PM
+           * states.
+           */
 
           return -EBUSY;
         }
diff --git a/drivers/analog/adc.c b/drivers/analog/adc.c
index a97d01f..e5b4010 100644
--- a/drivers/analog/adc.c
+++ b/drivers/analog/adc.c
@@ -138,7 +138,9 @@ static int adc_open(FAR struct file *filep)
         }
       else
         {
-          /* Check if this is the first time that the driver has been opened. */
+          /* Check if this is the first time that the driver has been
+           * opened.
+           */
 
           if (tmp == 1)
             {
@@ -323,7 +325,7 @@ static ssize_t adc_read(FAR struct file *filep, FAR char *buffer,
 
           if (msglen == 1)
             {
-              /* Only one channel, return MS 8-bits of the sample*/
+              /* Only one channel, return MS 8-bits of the sample. */
 
               buffer[nread] = msg->am_data >> 24;
             }
diff --git a/drivers/analog/comp.c b/drivers/analog/comp.c
index 61e6701..2365bc4 100644
--- a/drivers/analog/comp.c
+++ b/drivers/analog/comp.c
@@ -274,7 +274,9 @@ static int comp_open(FAR struct file *filep)
         }
       else
         {
-          /* Check if this is the first time that the driver has been opened. */
+          /* Check if this is the first time that the driver has been
+           * opened.
+           */
 
           if (tmp == 1)
             {
diff --git a/drivers/analog/dac.c b/drivers/analog/dac.c
index 908ebfe..b0ea4cd 100644
--- a/drivers/analog/dac.c
+++ b/drivers/analog/dac.c
@@ -133,7 +133,9 @@ static int dac_open(FAR struct file *filep)
         }
       else
         {
-          /* Check if this is the first time that the driver has been opened. */
+          /* Check if this is the first time that the driver has been
+           * opened.
+           */
 
           if (tmp == 1)
             {
@@ -330,7 +332,9 @@ static ssize_t dac_write(FAR struct file *filep, FAR const char *buffer,
           nexttail = 0;
         }
 
-      /* If the XMIT fifo becomes full, then wait for space to become available */
+      /* If the XMIT fifo becomes full, then wait for space to become
+       * available.
+       */
 
       while (nexttail == fifo->af_head)
         {
diff --git a/drivers/can/can.c b/drivers/can/can.c
index 334ba7c..2a6e004 100644
--- a/drivers/can/can.c
+++ b/drivers/can/can.c
@@ -834,7 +834,9 @@ static ssize_t can_write(FAR struct file *filep, FAR const char *buffer,
           nexttail = 0;
         }
 
-      /* If the XMIT FIFO becomes full, then wait for space to become available */
+      /* If the XMIT FIFO becomes full, then wait for space to become
+       * available.
+       */
 
       while (nexttail == fifo->tx_head)
         {
diff --git a/drivers/input/ads7843e.c b/drivers/input/ads7843e.c
index 95ccc48..0a9b203 100644
--- a/drivers/input/ads7843e.c
+++ b/drivers/input/ads7843e.c
@@ -644,7 +644,9 @@ static void ads7843e_worker(FAR void *arg)
 
       if (xdiff < CONFIG_ADS7843E_THRESHX && ydiff < CONFIG_ADS7843E_THRESHY)
         {
-          /* Little or no change in either direction ... don't report anything. */
+          /* Little or no change in either direction ... don't report
+           * anything.
+           */
 
           goto ignored;
         }
diff --git a/drivers/input/max11802.c b/drivers/input/max11802.c
index 2a53ce6..911ee63 100644
--- a/drivers/input/max11802.c
+++ b/drivers/input/max11802.c
@@ -641,11 +641,15 @@ static void max11802_worker(FAR void *arg)
       xdiff = x > priv->threshx ? (x - priv->threshx) : (priv->threshx - x);
       ydiff = y > priv->threshy ? (y - priv->threshy) : (priv->threshy - y);
 
-      /* Check the thresholds.  Bail if there is no significant difference */
+      /* Check the thresholds.  Bail if there is no significant
+       * difference.
+       */
 
       if (xdiff < CONFIG_MAX11802_THRESHX && ydiff < CONFIG_MAX11802_THRESHY)
         {
-          /* Little or no change in either direction ... don't report anything. */
+          /* Little or no change in either direction ... don't report
+           * anything.
+           */
 
           goto ignored;
         }
diff --git a/drivers/input/tsc2007.c b/drivers/input/tsc2007.c
index ac05269..27fc504 100644
--- a/drivers/input/tsc2007.c
+++ b/drivers/input/tsc2007.c
@@ -1,46 +1,31 @@
 /****************************************************************************
  * drivers/input/tsc2007.c
  *
- *   Copyright (C) 2011-2012, 2016-2017 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
  *
- * References:
- *   "1.2V to 3.6V, 12-Bit, Nanopower, 4-Wire Micro TOUCH SCREEN CONTROLLER
- *    with I2C Interface," SBAS405A March 2007, Revised, March 2009, Texas
- *    Instruments Incorporated
- *
- * 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.
  *
  ****************************************************************************/
 
 /* The TSC2007 is an analog interface circuit for a human interface touch
  * screen device. All peripheral functions are controlled through the command
  * byte and onboard state machines.
+ *
+ * References:
+ *   "1.2V to 3.6V, 12-Bit, Nanopower, 4-Wire Micro TOUCH SCREEN CONTROLLER
+ *    with I2C Interface," SBAS405A March 2007, Revised, March 2009, Texas
+ *    Instruments Incorporated
  */
 
 /****************************************************************************
@@ -79,7 +64,9 @@
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
+
 /* Configuration ************************************************************/
+
 /* Reference counting is partially implemented, but not needed in the
  * current design.
  */
@@ -95,6 +82,7 @@
 #define CONFIG_TSC2007_ACTIVATE 1
 
 /* Driver support ***********************************************************/
+
 /* This format is used to construct the /dev/input[n] device driver path.  It
  * defined here so that it will be used consistently in all places.
  */
@@ -200,9 +188,11 @@ static int tsc2007_interrupt(int irq, FAR void *context);
 
 static int tsc2007_open(FAR struct file *filep);
 static int tsc2007_close(FAR struct file *filep);
-static ssize_t tsc2007_read(FAR struct file *filep, FAR char *buffer, size_t len);
+static ssize_t tsc2007_read(FAR struct file *filep, FAR char *buffer,
+                            size_t len);
 static int tsc2007_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
-static int tsc2007_poll(FAR struct file *filep, struct pollfd *fds, bool setup);
+static int tsc2007_poll(FAR struct file *filep, struct pollfd *fds,
+                        bool setup);
 
 /****************************************************************************
  * Private Data
@@ -259,10 +249,10 @@ static void tsc2007_notify(FAR struct tsc2007_dev_s *priv)
       nxsem_post(&priv->waitsem);
     }
 
-  /* If there are threads waiting on poll() for TSC2007 data to become available,
-   * then wake them up now.  NOTE: we wake up all waiting threads because we
-   * do not know that they are going to do.  If they all try to read the data,
-   * then some make end up blocking after all.
+  /* If there are threads waiting on poll() for TSC2007 data to become
+   * available, then wake them up now.  NOTE: we wake up all waiting
+   * threads because we do not know that they are going to do.  If they
+   * all try to read the data, then some make end up blocking after all.
    */
 
   for (i = 0; i < CONFIG_TSC2007_NPOLLWAITERS; i++)
@@ -317,11 +307,11 @@ static int tsc2007_sample(FAR struct tsc2007_dev_s *priv,
           priv->id++;
         }
       else if (sample->contact == CONTACT_DOWN)
-       {
+        {
           /* First report -- next report will be a movement */
 
-         priv->sample.contact = CONTACT_MOVE;
-       }
+          priv->sample.contact = CONTACT_MOVE;
+        }
 
       priv->penchange = false;
       ret = OK;
@@ -379,8 +369,8 @@ static int tsc2007_waitsample(FAR struct tsc2007_dev_s *priv,
     }
 
   /* Re-acquire the semaphore that manages mutually exclusive access to
-   * the device structure.  We may have to wait here.  But we have our sample.
-   * Interrupts and pre-emption will be re-enabled while we wait.
+   * the device structure.  We may have to wait here.  But we have our
+   * sample.  Interrupts and pre-emption will be re-enabled while we wait.
    */
 
   ret = nxsem_wait(&priv->devsem);
@@ -410,42 +400,43 @@ errout:
 #ifdef CONFIG_TSC2007_ACTIVATE
 static int tsc2007_activate(FAR struct tsc2007_dev_s *priv, uint8_t cmd)
 {
-   struct i2c_msg_s msg;
-   uint8_t data;
-   int ret;
+  struct i2c_msg_s msg;
+  uint8_t data;
+  int ret;
 
   /* Send the setup command (with no ACK) followed by the A/D converter
    * activation command (ACKed).
    */
 
-   data          = TSC2007_SETUP;
+  data          = TSC2007_SETUP;
 
-   msg.frequency = priv->config->frequency;   /* I2C frequency */
-   msg.addr      = priv->config->address;     /* 7-bit address */
-   msg.flags     = 0;                         /* Write transaction, beginning with START */
-   msg.buffer    = &data;                     /* Transfer from this address */
-   msg.length    = 1;                         /* Send one byte following the address */
+  msg.frequency = priv->config->frequency;   /* I2C frequency */
+  msg.addr      = priv->config->address;     /* 7-bit address */
+  msg.flags     = 0;                         /* Write transaction, beginning with START */
+  msg.buffer    = &data;                     /* Transfer from this address */
+  msg.length    = 1;                         /* Send one byte following the address */
 
-   /* Ignore errors from the setup command (because it is not ACKed) */
+  /* Ignore errors from the setup command (because it is not ACKed) */
 
-   I2C_TRANSFER(priv->i2c, &msg, 1);
+  I2C_TRANSFER(priv->i2c, &msg, 1);
 
-   /* Now activate the A/D converter */
+  /* Now activate the A/D converter */
 
-   data          = cmd;
+  data          = cmd;
 
-   msg.frequency = priv->config->frequency;   /* I2C frequency */
-   msg.addr      = priv->config->address;     /* 7-bit address */
-   msg.flags     = 0;                         /* Write transaction, beginning with START */
-   msg.buffer    = &data;                     /* Transfer from this address */
-   msg.length    = 1;                         /* Send one byte following the address */
+  msg.frequency = priv->config->frequency;   /* I2C frequency */
+  msg.addr      = priv->config->address;     /* 7-bit address */
+  msg.flags     = 0;                         /* Write transaction, beginning with START */
+  msg.buffer    = &data;                     /* Transfer from this address */
+  msg.length    = 1;                         /* Send one byte following the address */
 
-   ret = I2C_TRANSFER(priv->i2c, &msg, 1);
-   if (ret < 0)
-     {
-       ierr("ERROR: I2C_TRANSFER failed: %d\n", ret);
-     }
-   return ret;
+  ret = I2C_TRANSFER(priv->i2c, &msg, 1);
+  if (ret < 0)
+    {
+      ierr("ERROR: I2C_TRANSFER failed: %d\n", ret);
+    }
+
+  return ret;
 }
 #else
 #  define tsc2007_activate(p,c)
@@ -457,9 +448,9 @@ static int tsc2007_activate(FAR struct tsc2007_dev_s *priv, uint8_t cmd)
 
 static int tsc2007_transfer(FAR struct tsc2007_dev_s *priv, uint8_t cmd)
 {
-   struct i2c_msg_s msg;
-   uint8_t data12[2];
-   int ret;
+  struct i2c_msg_s msg;
+  uint8_t data12[2];
+  int ret;
 
   /* "A conversion/write cycle begins when the master issues the address
    *  byte containing the slave address of the TSC2007, with the eighth bit
@@ -473,18 +464,18 @@ static int tsc2007_transfer(FAR struct tsc2007_dev_s *priv, uint8_t cmd)
    *  STOP condition...
    */
 
-   msg.frequency = priv->config->frequency;   /* I2C frequency */
-   msg.addr      = priv->config->address;     /* 7-bit address */
-   msg.flags     = 0;                         /* Write transaction, beginning with START */
-   msg.buffer    = &cmd;                      /* Transfer from this address */
-   msg.length    = 1;                         /* Send one byte following the address */
+  msg.frequency = priv->config->frequency;   /* I2C frequency */
+  msg.addr      = priv->config->address;     /* 7-bit address */
+  msg.flags     = 0;                         /* Write transaction, beginning with START */
+  msg.buffer    = &cmd;                      /* Transfer from this address */
+  msg.length    = 1;                         /* Send one byte following the address */
 
-   ret = I2C_TRANSFER(priv->i2c, &msg, 1);
-   if (ret < 0)
-     {
-       ierr("ERROR: I2C_TRANSFER failed: %d\n", ret);
-       return ret;
-     }
+  ret = I2C_TRANSFER(priv->i2c, &msg, 1);
+  if (ret < 0)
+    {
+      ierr("ERROR: I2C_TRANSFER failed: %d\n", ret);
+      return ret;
+    }
 
   /* "The input multiplexer channel for the A/D converter is selected when
    *  bits C3 through C0 are clocked in. If the selected channel is an X-,Y-,
@@ -501,7 +492,7 @@ static int tsc2007_transfer(FAR struct tsc2007_dev_s *priv, uint8_t cmd)
    *  least 10ms before attempting to read data from the TSC2007...
    */
 
-  nxsig_usleep(10*1000);
+  nxsig_usleep(10 * 1000);
 
   /* "Data access begins with the master issuing a START condition followed
    *  by the address byte ... with R/W = 1.
@@ -510,35 +501,35 @@ static int tsc2007_transfer(FAR struct tsc2007_dev_s *priv, uint8_t cmd)
    *  slave issues an acknowledge. The first byte of serial data then follows
    *  (D11-D4, MSB first).
    *
-   * "After the first byte has been sent by the slave, it releases the SDA line
-   *  for the master to issue an acknowledge.  The slave responds with the
-   *  second byte of serial data upon receiving the acknowledge from the master
-   *  (D3-D0, followed by four 0 bits). The second byte is followed by a NOT
-   *  acknowledge bit (ACK = 1) from the master to indicate that the last
-   *  data byte has been received...
+   * "After the first byte has been sent by the slave, it releases the SDA
+   *  line for the master to issue an acknowledge.  The slave responds with
+   *  the second byte of serial data upon receiving the acknowledge from the
+   *  master (D3-D0, followed by four 0 bits). The second byte is followed by
+   *  a NOT acknowledge bit (ACK = 1) from the master to indicate that the
+   *  last data byte has been received...
    */
 
-   msg.frequency = priv->config->frequency;   /* I2C frequency */
-   msg.addr      = priv->config->address;     /* 7-bit address */
-   msg.flags     = I2C_M_READ;                /* Read transaction, beginning with START */
-   msg.buffer    = data12;                    /* Transfer to this address */
-   msg.length    = 2;                         /* Read two bytes following the address */
+  msg.frequency = priv->config->frequency;   /* I2C frequency */
+  msg.addr      = priv->config->address;     /* 7-bit address */
+  msg.flags     = I2C_M_READ;                /* Read transaction, beginning with START */
+  msg.buffer    = data12;                    /* Transfer to this address */
+  msg.length    = 2;                         /* Read two bytes following the address */
 
-   ret = I2C_TRANSFER(priv->i2c, &msg, 1);
-   if (ret < 0)
-     {
-       ierr("ERROR: I2C_TRANSFER failed: %d\n", ret);
-       return ret;
-     }
+  ret = I2C_TRANSFER(priv->i2c, &msg, 1);
+  if (ret < 0)
+    {
+      ierr("ERROR: I2C_TRANSFER failed: %d\n", ret);
+      return ret;
+    }
 
   /* Get the MS 8 bits from the first byte and the remaining LS 4 bits from
    * the second byte.  The valid range of data is then from 0 to 4095 with
    * the LSB unit corresponding to Vref/4096.
    */
 
-   ret = (unsigned int)data12[0] << 4 | (unsigned int)data12[1] >> 4;
-   iinfo("data: 0x%04x\n", ret);
-   return ret;
+  ret = (unsigned int)data12[0] << 4 | (unsigned int)data12[1] >> 4;
+  iinfo("data: 0x%04x\n", ret);
+  return ret;
 }
 
 /****************************************************************************
@@ -573,8 +564,9 @@ static void tsc2007_worker(FAR void *arg)
 
   if (!pendown)
     {
-      /* Ignore the interrupt if the pen was already down (CONTACT_NONE == pen up and
-       * already reported.  CONTACT_UP == pen up, but not reported)
+      /* Ignore the interrupt if the pen was already down (CONTACT_NONE ==
+       * pen up and already reported.  CONTACT_UP == pen up, but not
+       * reported)
        */
 
       if (priv->sample.contact == CONTACT_NONE)
@@ -584,13 +576,13 @@ static void tsc2007_worker(FAR void *arg)
     }
 
   /* It is a pen down event.  If the last loss-of-contact event has not been
-   * processed yet, then we have to ignore the pen down event (or else it will
-   * look like a drag event)
+   * processed yet, then we have to ignore the pen down event (or else it
+   * will look like a drag event)
    */
 
   else if (priv->sample.contact == CONTACT_UP)
     {
-       goto errout;
+      goto errout;
     }
   else
     {
@@ -598,47 +590,50 @@ static void tsc2007_worker(FAR void *arg)
        *
        * "A resistive touch screen operates by applying a voltage across a
        *  resistor network and measuring the change in resistance at a given
-       *  point on the matrix where the screen is touched by an input (stylus,
-       *  pen, or finger). The change in the resistance ratio marks the location
-       *  on the touch screen.
+       *  point on the matrix where the screen is touched by an input
+       *  (stylus, pen, or finger). The change in the resistance ratio marks
+       *  the location on the touch screen.
        *
-       * "The 4-wire touch screen panel works by applying a voltage across the
-       *  vertical or horizontal resistive network.  The A/D converter converts
-       *  the voltage measured at the point where the panel is touched. A measurement
-       *  of the Y position of the pointing device is made by connecting the X+
-       *  input to a data converter chip, turning on the Y+ and Y- drivers, and
-       *  digitizing the voltage seen at the X+ input ..."
+       * "The 4-wire touch screen panel works by applying a voltage across
+       *  the vertical or horizontal resistive network.  The A/D converter
+       *  converts the voltage measured at the point where the panel is
+       *  touched. A measurement of the Y position of the pointing device is
+       *  made by connecting the X+ input to a data converter chip, turning
+       *  on the Y+ and Y- drivers, and digitizing the voltage seen at the
+       *  X+ input ..."
        *
-       * "... it is recommended that whenever the host writes to the TSC2007, the
-       *  master processor masks the interrupt associated to PENIRQ. This masking
-       *  prevents false triggering of interrupts when the PENIRQ line is disabled
-       *  in the cases previously listed."
+       * "... it is recommended that whenever the host writes to the TSC2007,
+       *  the master processor masks the interrupt associated to PENIRQ.
+       *  This masking prevents false triggering of interrupts when the
+       *  PENIRQ line is disabled in the cases previously listed."
        */
 
       tsc2007_activate(priv, TSC2007_ACTIVATE_X);
       y = tsc2007_transfer(priv, TSC2007_MEASURE_Y);
 
-
       /* "Voltage is then applied to the other axis, and the A/D converter
-       *  converts the voltage representing the X position on the screen. This
-       *  process provides the X and Y coordinates to the associated processor."
+       *  converts the voltage representing the X position on the screen.
+       *  This process provides the X and Y coordinates to the associated
+       *  processor."
        */
 
       tsc2007_activate(priv, TSC2007_ACTIVATE_Y);
       x = tsc2007_transfer(priv, TSC2007_MEASURE_X);
 
-      /* "... To determine pen or finger touch, the pressure of the touch must be
-       *  determined. ... There are several different ways of performing this
-       *  measurement. The TSC2007 supports two methods. The first method requires
-       *  knowing the X-plate resistance, the measurement of the X-position, and two
-       *  additional cross panel measurements (Z2 and Z1) of the touch screen."
+      /* "... To determine pen or finger touch, the pressure of the touch
+       *  must be determined. ... There are several different ways of
+       *  performing this measurement. The TSC2007 supports two methods.  The
+       *  first method requires knowing the X-plate resistance, the
+       *  measurement of the X-position, and two additional cross panel
+       *  measurements (Z2 and Z1) of the touch screen."
        *
        *  Rtouch = Rxplate * (X / 4096)* (Z2/Z1 - 1)
        *
        * "The second method requires knowing both the X-plate and Y-plate
        *  resistance, measurement of X-position and Y-position, and Z1 ..."
        *
-       *  Rtouch = Rxplate * (X / 4096) * (4096/Z1 - 1) - Ryplate * (1 - Y/4096)
+       *  Rtouch = Rxplate * (X / 4096) * (4096/Z1 - 1) -
+       *           Ryplate * (1 - Y/4096)
        *
        * Read Z1 and Z2 values.
        */
@@ -880,7 +875,8 @@ static int tsc2007_close(FAR struct file *filep)
  * Name: tsc2007_read
  ****************************************************************************/
 
-static ssize_t tsc2007_read(FAR struct file *filep, FAR char *buffer, size_t len)
+static ssize_t tsc2007_read(FAR struct file *filep, FAR char *buffer,
+                            size_t len)
 {
   FAR struct inode          *inode;
   FAR struct tsc2007_dev_s  *priv;
@@ -930,7 +926,7 @@ static ssize_t tsc2007_read(FAR struct file *filep, FAR char *buffer, size_t len
         {
           ret = -EAGAIN;
           goto errout;
-       }
+        }
 
       /* Wait for sample data */
 
@@ -980,16 +976,20 @@ static ssize_t tsc2007_read(FAR struct file *filep, FAR char *buffer, size_t len
         {
           /* Loss of contact */
 
-          report->point[0].flags  = TOUCH_DOWN | TOUCH_ID_VALID | TOUCH_POS_VALID;
+          report->point[0].flags  = TOUCH_DOWN | TOUCH_ID_VALID |
+                                    TOUCH_POS_VALID;
         }
       else /* if (sample->contact == CONTACT_MOVE) */
         {
           /* Movement of the same contact */
 
-          report->point[0].flags  = TOUCH_MOVE | TOUCH_ID_VALID | TOUCH_POS_VALID;
+          report->point[0].flags  = TOUCH_MOVE | TOUCH_ID_VALID |
+                                    TOUCH_POS_VALID;
         }
 
-      /* A pressure measurement of zero means that pressure is not available */
+      /* A pressure measurement of zero means that pressure is not
+       * available.
+       */
 
       if (report->point[0].pressure != 0)
         {
@@ -1212,7 +1212,8 @@ int tsc2007_register(FAR struct i2c_master_s *dev,
 #ifndef CONFIG_TSC2007_MULTIPLE
   priv = &g_tsc2007;
 #else
-  priv = (FAR struct tsc2007_dev_s *)kmm_malloc(sizeof(struct tsc2007_dev_s));
+  priv = (FAR struct tsc2007_dev_s *)
+    kmm_malloc(sizeof(struct tsc2007_dev_s));
   if (!priv)
     {
       ierr("ERROR: kmm_malloc(%d) failed\n", sizeof(struct tsc2007_dev_s));
diff --git a/drivers/net/rpmsgdrv.c b/drivers/net/rpmsgdrv.c
index 3bf5d58..5efec3c 100644
--- a/drivers/net/rpmsgdrv.c
+++ b/drivers/net/rpmsgdrv.c
@@ -141,7 +141,9 @@
 #  define net_rpmsg_drv_dumppacket(m, b, l)
 #endif
 
-/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */
+/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per
+ * second.
+ */
 
 #define NET_RPMSG_DRV_WDDELAY      (1*CLK_TCK)
 
@@ -379,8 +381,8 @@ static int net_rpmsg_drv_txpoll(FAR struct net_driver_s *dev)
 
           net_rpmsg_drv_transmit(dev, true);
 
-          /* Check if there is room in the device to hold another packet. If not,
-           * return a non-zero value to terminate the poll.
+          /* Check if there is room in the device to hold another packet. If
+           * not, return a non-zero value to terminate the poll.
            */
 
           dev->d_buf = rpmsg_get_tx_payload_buffer(&priv->ept, &size, false);
@@ -394,8 +396,8 @@ static int net_rpmsg_drv_txpoll(FAR struct net_driver_s *dev)
         }
     }
 
-  /* If zero is returned, the polling will continue until all connections have
-   * been examined.
+  /* If zero is returned, the polling will continue until all connections
+   * have been examined.
    */
 
   return 0;
@@ -492,7 +494,8 @@ static int net_rpmsg_drv_sockioctl_task(int argc, FAR char *argv[])
   msg->header.result = psock_socket(domain, type, protocol, &sock);
   if (msg->header.result >= 0)
     {
-      msg->header.result = psock_ioctl(&sock, msg->code, (unsigned long)msg->arg);
+      msg->header.result = psock_ioctl(&sock, msg->code,
+                                       (unsigned long)msg->arg);
       psock_close(&sock); /* Close the temporary sock */
     }
 
@@ -536,7 +539,8 @@ static int net_rpmsg_drv_sockioctl_handler(FAR struct rpmsg_endpoint *ept,
 #ifdef CONFIG_NET_IPv4
 static bool net_rpmsg_drv_is_ipv4(FAR struct net_driver_s *dev)
 {
-  FAR struct ipv4_hdr_s *ip = (struct ipv4_hdr_s *)(dev->d_buf + dev->d_llhdrlen);
+  FAR struct ipv4_hdr_s *ip =
+    (struct ipv4_hdr_s *)(dev->d_buf + dev->d_llhdrlen);
   FAR struct eth_hdr_s *eth = (struct eth_hdr_s *)dev->d_buf;
 
   if (dev->d_lltype == NET_LL_ETHERNET || dev->d_lltype == NET_LL_IEEE80211)
@@ -553,7 +557,8 @@ static bool net_rpmsg_drv_is_ipv4(FAR struct net_driver_s *dev)
 #ifdef CONFIG_NET_IPv6
 static bool net_rpmsg_drv_is_ipv6(FAR struct net_driver_s *dev)
 {
-  FAR struct ipv6_hdr_s *ip = (struct ipv6_hdr_s *)(dev->d_buf + dev->d_llhdrlen);
+  FAR struct ipv6_hdr_s *ip =
+    (struct ipv6_hdr_s *)(dev->d_buf + dev->d_llhdrlen);
   FAR struct eth_hdr_s *eth = (struct eth_hdr_s *)dev->d_buf;
 
   if (dev->d_lltype == NET_LL_ETHERNET || dev->d_lltype == NET_LL_IEEE80211)
@@ -737,7 +742,8 @@ static int net_rpmsg_drv_ept_cb(FAR struct rpmsg_endpoint *ept, void *data,
   FAR struct net_rpmsg_header_s *header = data;
   uint32_t command = header->command;
 
-  if (command < sizeof(g_net_rpmsg_drv_handler) / sizeof(g_net_rpmsg_drv_handler[0]))
+  if (command < sizeof(g_net_rpmsg_drv_handler) /
+                sizeof(g_net_rpmsg_drv_handler[0]))
     {
       return g_net_rpmsg_drv_handler[command](ept, data, len, src, priv);
     }
@@ -827,9 +833,9 @@ static void net_rpmsg_drv_poll_work(FAR void *arg)
 
   if (dev->d_buf)
     {
-      /* If so, update TCP timing states and poll the network for new XMIT data.
-       * Hmmm.. might be bug here.  Does this mean if there is a transmit in
-       * progress, we will missing TCP time state updates?
+      /* If so, update TCP timing states and poll the network for new XMIT
+       * data.  Hmmm.. might be bug here.  Does this mean if there is a
+       * transmit in progress, we will missing TCP time state updates?
        */
 
       devif_timer(dev, NET_RPMSG_DRV_WDDELAY, net_rpmsg_drv_txpoll);
@@ -979,7 +985,8 @@ static int net_rpmsg_drv_ifup(FAR struct net_driver_s *dev)
       dnsaddr.sin_port   = htons(DNS_DEFAULT_PORT);
       memcpy(&dnsaddr.sin_addr, &msg.dnsaddr, sizeof(msg.dnsaddr));
 
-      dns_add_nameserver((FAR const struct sockaddr *)&dnsaddr, sizeof(dnsaddr));
+      dns_add_nameserver((FAR const struct sockaddr *)&dnsaddr,
+                         sizeof(dnsaddr));
     }
 #  endif
 
@@ -994,7 +1001,8 @@ static int net_rpmsg_drv_ifup(FAR struct net_driver_s *dev)
       dnsaddr.sin6_port   = htons(DNS_DEFAULT_PORT);
       memcpy(&dnsaddr.sin6_addr, msg.ipv6dnsaddr, sizeof(msg.ipv6dnsaddr));
 
-      dns_add_nameserver((FAR const struct sockaddr *)&dnsaddr, sizeof(dnsaddr));
+      dns_add_nameserver((FAR const struct sockaddr *)&dnsaddr,
+                         sizeof(dnsaddr));
     }
 #  endif
 #endif
@@ -1037,8 +1045,8 @@ static int net_rpmsg_drv_ifdown(FAR struct net_driver_s *dev)
   leave_critical_section(flags);
 
   /* Put the EMAC in its reset, non-operational state.  This should be
-   * a known configuration that will guarantee the net_rpmsg_drv_ifup() always
-   * successfully brings the interface back up.
+   * a known configuration that will guarantee the net_rpmsg_drv_ifup()
+   * always successfully brings the interface back up.
    */
 
   return net_rpmsg_drv_send_recv(dev, &msg, NET_RPMSG_IFDOWN, sizeof(msg));
@@ -1091,7 +1099,9 @@ static void net_rpmsg_drv_txavail_work(FAR void *arg)
             }
         }
 
-      /* Check if there is room in the hardware to hold another outgoing packet. */
+      /* Check if there is room in the hardware to hold another outgoing
+       * packet.
+       */
 
       if (dev->d_buf)
         {
@@ -1136,7 +1146,8 @@ static int net_rpmsg_drv_txavail(FAR struct net_driver_s *dev)
     {
       /* Schedule to serialize the poll on the worker thread. */
 
-      work_queue(LPWORK, &priv->pollwork, net_rpmsg_drv_txavail_work, dev, 0);
+      work_queue(LPWORK, &priv->pollwork, net_rpmsg_drv_txavail_work,
+                 dev, 0);
     }
 
   return OK;
@@ -1176,8 +1187,8 @@ static int net_rpmsg_drv_addmac(FAR struct net_driver_s *dev,
  * Name: net_rpmsg_drv_rmmac
  *
  * Description:
- *   NuttX Callback: Remove the specified MAC address from the hardware multicast
- *   address filtering
+ *   NuttX Callback: Remove the specified MAC address from the hardware
+ *   multicast address filtering
  *
  * Parameters:
  *   dev  - Reference to the NuttX driver state structure
diff --git a/drivers/net/tun.c b/drivers/net/tun.c
index bfc2389..6794da1 100644
--- a/drivers/net/tun.c
+++ b/drivers/net/tun.c
@@ -111,7 +111,9 @@
 
 #define TUN_WDDELAY  (1 * CLK_TCK)
 
-/* This is a helper pointer for accessing the contents of the Ethernet header */
+/* This is a helper pointer for accessing the contents of the Ethernet
+ * header.
+ */
 
 #ifdef CONFIG_NET_ETHERNET
 #  define BUF ((FAR struct eth_hdr_s *)priv->dev.d_buf)
diff --git a/drivers/pipes/pipe_common.c b/drivers/pipes/pipe_common.c
index 6f98f75..e21f169 100644
--- a/drivers/pipes/pipe_common.c
+++ b/drivers/pipes/pipe_common.c
@@ -205,7 +205,9 @@ int pipecommon_open(FAR struct file *filep)
         }
     }
 
-  /* If opened for writing, increment the count of writers on the pipe instance */
+  /* If opened for writing, increment the count of writers on the pipe
+   * instance.
+   */
 
   if ((filep->f_oflags & O_WROK) != 0)
     {
@@ -225,7 +227,9 @@ int pipecommon_open(FAR struct file *filep)
         }
     }
 
-  /* If opened for reading, increment the count of reader on on the pipe instance */
+  /* If opened for reading, increment the count of reader on on the pipe
+   * instance.
+   */
 
   if ((filep->f_oflags & O_RDOK) != 0)
     {
@@ -455,7 +459,9 @@ ssize_t pipecommon_read(FAR struct file *filep, FAR char *buffer, size_t len)
         }
     }
 
-  /* Then return whatever is available in the pipe (which is at least one byte) */
+  /* Then return whatever is available in the pipe (which is at least one
+   * byte).
+   */
 
   nread = 0;
   while ((size_t)nread < len && dev->d_wrndx != dev->d_rdndx)
@@ -469,7 +475,9 @@ ssize_t pipecommon_read(FAR struct file *filep, FAR char *buffer, size_t len)
       nread++;
     }
 
-  /* Notify all waiting writers that bytes have been removed from the buffer */
+  /* Notify all waiting writers that bytes have been removed from the
+   * buffer.
+   */
 
   while (nxsem_get_value(&dev->d_wrsem, &sval) == 0 && sval < 0)
     {
@@ -575,14 +583,18 @@ ssize_t pipecommon_write(FAR struct file *filep, FAR const char *buffer,
           nwritten++;
           if ((size_t)nwritten >= len)
             {
-              /* Yes.. Notify all of the waiting readers that more data is available */
+              /* Yes.. Notify all of the waiting readers that more data is
+               * available.
+               */
 
               while (nxsem_get_value(&dev->d_rdsem, &sval) == 0 && sval < 0)
                 {
                   nxsem_post(&dev->d_rdsem);
                 }
 
-              /* Notify all poll/select waiters that they can read from the FIFO */
+              /* Notify all poll/select waiters that they can read from the
+               * FIFO.
+               */
 
               pipecommon_pollnotify(dev, POLLIN);
 
@@ -594,25 +606,33 @@ ssize_t pipecommon_write(FAR struct file *filep, FAR const char *buffer,
         }
       else
         {
-          /* There is not enough room for the next byte.  Was anything written in this pass? */
+          /* There is not enough room for the next byte.  Was anything
+           * written in this pass?
+           */
 
           if (last < nwritten)
             {
-              /* Yes.. Notify all of the waiting readers that more data is available */
+              /* Yes.. Notify all of the waiting readers that more data is
+               * available.
+               */
 
               while (nxsem_get_value(&dev->d_rdsem, &sval) == 0 && sval < 0)
                 {
                   nxsem_post(&dev->d_rdsem);
                 }
 
-              /* Notify all poll/select waiters that they can read from the FIFO */
+              /* Notify all poll/select waiters that they can read from the
+               * FIFO.
+               */
 
               pipecommon_pollnotify(dev, POLLIN);
             }
 
           last = nwritten;
 
-          /* If O_NONBLOCK was set, then return partial bytes written or EGAIN */
+          /* If O_NONBLOCK was set, then return partial bytes written or
+           * EGAIN.
+           */
 
           if (filep->f_oflags & O_NONBLOCK)
             {
diff --git a/drivers/sensors/lis3dh.c b/drivers/sensors/lis3dh.c
index c8be9e7..7a8cb92 100644
--- a/drivers/sensors/lis3dh.c
+++ b/drivers/sensors/lis3dh.c
@@ -99,7 +99,8 @@ static void lis3dh_write_register(FAR struct lis3dh_dev_s *dev,
 static void lis3dh_reset(FAR struct lis3dh_dev_s *dev);
 static int lis3dh_ident(FAR struct lis3dh_dev_s *dev);
 static int lis3dh_read_fifo(FAR struct lis3dh_dev_s *dev);
-static int lis3dh_interrupt_handler(int irq, FAR void *context, FAR void *arg);
+static int lis3dh_interrupt_handler(int irq, FAR void *context,
+                                    FAR void *arg);
 static void lis3dh_worker(FAR void *arg);
 static int lis3dh_irq_enable(FAR struct lis3dh_dev_s *dev, bool enable);
 static int lis3dh_fifo_enable(FAR struct lis3dh_dev_s *dev);
@@ -152,7 +153,9 @@ static void lis3dh_read_register(FAR struct lis3dh_dev_s *dev,
 {
   uint8_t buffer[2];
 
-  /* Lock the SPI bus so that only one device can access it at the same time */
+  /* Lock the SPI bus so that only one device can access it at the same
+   * time.
+   */
 
   SPI_LOCK(dev->spi, true);
 
@@ -193,7 +196,9 @@ static void lis3dh_write_register(FAR struct lis3dh_dev_s *dev,
 {
   uint8_t buffer[2];
 
-  /* Lock the SPI bus so that only one device can access it at the same time */
+  /* Lock the SPI bus so that only one device can access it at the same
+   * time.
+   */
 
   SPI_LOCK(dev->spi, true);
 
@@ -501,7 +506,8 @@ static int lis3dh_read_fifo(FAR struct lis3dh_dev_s *dev)
  *
  ****************************************************************************/
 
-static int lis3dh_interrupt_handler(int irq, FAR void *context, FAR void *arg)
+static int lis3dh_interrupt_handler(int irq, FAR void *context,
+                                    FAR void *arg)
 {
   /* The interrupt handler is called when the FIFO watermark is reached */
 
diff --git a/drivers/serial/pty.c b/drivers/serial/pty.c
index 5e69e6d..9876c16 100644
--- a/drivers/serial/pty.c
+++ b/drivers/serial/pty.c
@@ -795,7 +795,8 @@ static int pty_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
 
                do
                  {
-                   DEBUGVERIFY(nxsem_get_value(&devpair->pp_slavesem, &sval));
+                   DEBUGVERIFY(nxsem_get_value(&devpair->pp_slavesem,
+                                               &sval));
                    if (sval < 0)
                      {
                        nxsem_post(&devpair->pp_slavesem);
diff --git a/drivers/syslog/ramlog.c b/drivers/syslog/ramlog.c
index 75601f3..a6ff6cc 100644
--- a/drivers/syslog/ramlog.c
+++ b/drivers/syslog/ramlog.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * drivers/syslog/ramlog.c
  *
- *   Copyright (C) 2012, 2016-2017 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.
  *
  ****************************************************************************/
 
@@ -212,6 +197,7 @@ static void ramlog_pollnotify(FAR struct ramlog_dev_s *priv,
               nxsem_post(fds->sem);
             }
         }
+
       leave_critical_section(flags);
     }
 }
@@ -259,7 +245,8 @@ static ssize_t ramlog_addchar(FAR struct ramlog_dev_s *priv, char ch)
  * Name: ramlog_read
  ****************************************************************************/
 
-static ssize_t ramlog_read(FAR struct file *filep, FAR char *buffer, size_t len)
+static ssize_t ramlog_read(FAR struct file *filep, FAR char *buffer,
+                           size_t len)
 {
   FAR struct inode *inode = filep->f_inode;
   FAR struct ramlog_dev_s *priv;
@@ -310,7 +297,9 @@ static ssize_t ramlog_read(FAR struct file *filep, FAR char *buffer, size_t len)
               break;
             }
 
-          /* If the driver was opened with O_NONBLOCK option, then don't wait. */
+          /* If the driver was opened with O_NONBLOCK option, then don't
+           * wait.
+           */
 
           if (filep->f_oflags & O_NONBLOCK)
             {
@@ -319,8 +308,9 @@ static ssize_t ramlog_read(FAR struct file *filep, FAR char *buffer, size_t len)
             }
 
           /* Otherwise, wait for something to be written to the circular
-           * buffer. Increment the number of waiters so that the ramlog_write()
-           * will note that it needs to post the semaphore to wake us up.
+           * buffer. Increment the number of waiters so that the
+           * ramlog_write() will note that it needs to post the semaphore
+           * to wake us up.
            */
 
           sched_lock();
@@ -419,7 +409,8 @@ errout_without_sem:
  * Name: ramlog_write
  ****************************************************************************/
 
-static ssize_t ramlog_write(FAR struct file *filep, FAR const char *buffer, size_t len)
+static ssize_t ramlog_write(FAR struct file *filep, FAR const char *buffer,
+                            size_t len)
 {
   FAR struct inode *inode = filep->f_inode;
   FAR struct ramlog_dev_s *priv;
@@ -508,7 +499,9 @@ static ssize_t ramlog_write(FAR struct file *filep, FAR const char *buffer, size
 
       if (readers_waken == 0)
         {
-          /* Notify all poll/select waiters that they can read from the FIFO */
+          /* Notify all poll/select waiters that they can read from the
+           * FIFO.
+           */
 
           ramlog_pollnotify(priv, POLLIN);
         }
@@ -592,23 +585,23 @@ int ramlog_poll(FAR struct file *filep, FAR struct pollfd *fds, bool setup)
       /* First, check if the receive buffer is not full. */
 
       if (next_head != priv->rl_tail)
-       {
-         eventset |= POLLOUT;
-       }
+        {
+          eventset |= POLLOUT;
+        }
 
       /* Check if the receive buffer is not empty. */
 
       if (priv->rl_head != priv->rl_tail)
-       {
-         eventset |= POLLIN;
-       }
+        {
+          eventset |= POLLIN;
+        }
+
       leave_critical_section(flags);
 
       if (eventset)
         {
           ramlog_pollnotify(priv, eventset);
         }
-
     }
   else if (fds->priv)
     {
diff --git a/drivers/timers/pwm.c b/drivers/timers/pwm.c
index b298490..585516a 100644
--- a/drivers/timers/pwm.c
+++ b/drivers/timers/pwm.c
@@ -458,7 +458,9 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
 
           memcpy(&upper->info, info, sizeof(struct pwm_info_s));
 
-          /* If PWM is already running, then re-start it with the new characteristics */
+          /* If PWM is already running, then re-start it with the new
+           * characteristics.
+           */
 
           if (upper->started)
             {
@@ -532,7 +534,9 @@ static int pwm_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
         }
         break;
 
-      /* Any unrecognized IOCTL commands might be platform-specific ioctl commands */
+      /* Any unrecognized IOCTL commands might be platform-specific ioctl
+       * commands.
+       */
 
       default:
         {
@@ -590,7 +594,9 @@ int pwm_register(FAR const char *path, FAR struct pwm_lowerhalf_s *dev)
       return -ENOMEM;
     }
 
-  /* Initialize the PWM device structure (it was already zeroed by kmm_zalloc()) */
+  /* Initialize the PWM device structure (it was already zeroed by
+   * kmm_zalloc()).
+   */
 
   nxsem_init(&upper->exclsem, 0, 1);
 #ifdef CONFIG_PWM_PULSECOUNT
diff --git a/drivers/timers/rpmsg_rtc.c b/drivers/timers/rpmsg_rtc.c
index 014894e..a17a245 100644
--- a/drivers/timers/rpmsg_rtc.c
+++ b/drivers/timers/rpmsg_rtc.c
@@ -131,32 +131,30 @@ struct rpmsg_rtc_lowerhalf_s
  ****************************************************************************/
 
 static void rpmsg_rtc_device_created(FAR struct rpmsg_device *rdev,
-                                     FAR void *priv);
+              FAR void *priv);
 static void rpmsg_rtc_device_destroy(FAR struct rpmsg_device *rdev,
-                                     FAR void *priv);
+              FAR void *priv);
 static void rpmsg_rtc_alarm_fire_handler(FAR struct rpmsg_endpoint *ept,
-                                         FAR void *data, size_t len,
-                                         uint32_t src, FAR void *priv);
+              FAR void *data, size_t len, uint32_t src, FAR void *priv);
 static int rpmsg_rtc_ept_cb(FAR struct rpmsg_endpoint *ept, FAR void *data,
-                            size_t len, uint32_t src, FAR void *priv);
+              size_t len, uint32_t src, FAR void *priv);
 
 static int rpmsg_rtc_send_recv(FAR struct rpmsg_rtc_lowerhalf_s *lower,
-                               uint32_t command,
-                               FAR struct rpmsg_rtc_header_s *msg, int len);
+              uint32_t command, FAR struct rpmsg_rtc_header_s *msg, int len);
 static int rpmsg_rtc_rdtime(FAR struct rtc_lowerhalf_s *lower,
-                            FAR struct rtc_time *rtctime);
+              FAR struct rtc_time *rtctime);
 static int rpmsg_rtc_settime(FAR struct rtc_lowerhalf_s *lower,
-                             FAR const struct rtc_time *rtctime);
+              FAR const struct rtc_time *rtctime);
 static bool rpmsg_rtc_havesettime(FAR struct rtc_lowerhalf_s *lower);
 #ifdef CONFIG_RTC_ALARM
 static int rpmsg_rtc_setalarm(FAR struct rtc_lowerhalf_s *lower_,
-                              FAR const struct lower_setalarm_s *alarminfo);
+              FAR const struct lower_setalarm_s *alarminfo);
 static int rpmsg_rtc_setrelative(FAR struct rtc_lowerhalf_s *lower,
-                                 FAR const struct lower_setrelative_s *relinfo);
+              FAR const struct lower_setrelative_s *relinfo);
 static int rpmsg_rtc_cancelalarm(FAR struct rtc_lowerhalf_s *lower,
-                                 int alarmid);
+              int alarmid);
 static int rpmsg_rtc_rdalarm(FAR struct rtc_lowerhalf_s *lower_,
-                             FAR struct lower_rdalarm_s *alarminfo);
+              FAR struct lower_rdalarm_s *alarminfo);
 #endif
 
 /****************************************************************************
@@ -337,8 +335,9 @@ static int rpmsg_rtc_setalarm(FAR struct rtc_lowerhalf_s *lower_,
   return ret;
 }
 
-static int rpmsg_rtc_setrelative(FAR struct rtc_lowerhalf_s *lower,
-                                 FAR const struct lower_setrelative_s *relinfo)
+static int
+  rpmsg_rtc_setrelative(FAR struct rtc_lowerhalf_s *lower,
+                        FAR const struct lower_setrelative_s *relinfo)
 {
   struct lower_setalarm_s alarminfo =
   {
diff --git a/drivers/usbhost/usbhost_xboxcontroller.c b/drivers/usbhost/usbhost_xboxcontroller.c
index ce4cc1f..a82e26a 100644
--- a/drivers/usbhost/usbhost_xboxcontroller.c
+++ b/drivers/usbhost/usbhost_xboxcontroller.c
@@ -766,7 +766,9 @@ static int usbhost_xboxcontroller_poll(int argc, char *argv[])
                   memcpy(priv->tbuffer, guide_button_report_ack,
                          sizeof(guide_button_report_ack));
 
-                  /* Ensure the sequence number is the same as the input packet. */
+                  /* Ensure the sequence number is the same as the input
+                   * packet.
+                   */
 
                   priv->tbuffer[2] = seq_num;
 
@@ -789,7 +791,9 @@ static int usbhost_xboxcontroller_poll(int argc, char *argv[])
 
             case USBHOST_BUTTON_DATA:
 
-              /* Ignore the controller data if no task has opened the driver. */
+              /* Ignore the controller data if no task has opened the
+               * driver.
+               */
 
               if (priv->open)
                 {
@@ -879,7 +883,9 @@ static int usbhost_xboxcontroller_poll(int argc, char *argv[])
 
                   priv->valid = true;
 
-                  /* Notify any waiters that new controller data is available */
+                  /* Notify any waiters that new controller data is
+                   * available.
+                   */
 
                   usbhost_pollnotify(priv);
 
@@ -1185,7 +1191,9 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
             uinfo("Interface descriptor\n");
             DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC);
 
-            /* Did we already find what we needed from a preceding interface? */
+            /* Did we already find what we needed from a preceding
+             * interface?
+             */
 
             if ((found & USBHOST_ALLFOUND) == USBHOST_ALLFOUND)
               {
@@ -1415,7 +1423,9 @@ static inline int usbhost_devinit(FAR struct usbhost_state_s *priv)
                                  (FAR char * const *)NULL);
   if (priv->pollpid < 0)
     {
-      /* Failed to started the poll thread... probably due to memory resources */
+      /* Failed to started the poll thread... probably due to memory
+       * resources.
+       */
 
       usbhost_givesem(&g_exclsem);
       ret = priv->pollpid;
@@ -1649,11 +1659,15 @@ static FAR struct usbhost_class_s *
           priv->usbclass.connect      = usbhost_connect;
           priv->usbclass.disconnected = usbhost_disconnected;
 
-          /* The initial reference count is 1... One reference is held by the driver */
+          /* The initial reference count is 1... One reference is held by the
+           * driver.
+           */
 
           priv->crefs = 1;
 
-          /* Initialize semaphores (this works okay in the interrupt context) */
+          /* Initialize semaphores (this works okay in the interrupt
+           * context).
+           */
 
           nxsem_init(&priv->exclsem, 0, 1);
           nxsem_init(&priv->waitsem, 0, 0);
@@ -1782,7 +1796,9 @@ static int usbhost_disconnected(struct usbhost_class_s *usbclass)
   priv->disconnected = true;
   uinfo("Disconnected\n");
 
-  /* Are there a thread(s) waiting for controller data that will never come? */
+  /* Are there a thread(s) waiting for controller data that will never
+   * come?
+   */
 
   for (i = 0; i < priv->nwaiters; i++)
     {
diff --git a/drivers/video/video.c b/drivers/video/video.c
index d5f319a..260b278 100644
--- a/drivers/video/video.c
+++ b/drivers/video/video.c
@@ -237,6 +237,7 @@ static const struct file_operations g_video_fops =
 };
 
 static bool is_initialized = false;
+static FAR void *video_handler;
 
 /****************************************************************************
  * Public Data
@@ -245,6 +246,7 @@ static bool is_initialized = false;
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
+
 static int video_lock(FAR sem_t *sem)
 {
   if (sem == NULL)
@@ -483,6 +485,7 @@ static int video_open(FAR struct file *filep)
     {
       priv->open_num++;
     }
+
   video_unlock(&priv->lock_open_num);
 
   return ret;
@@ -507,6 +510,7 @@ static int video_close(FAR struct file *filep)
       cleanup_resources(priv);
       g_video_devops->close();
     }
+
   video_unlock(&priv->lock_open_num);
 
   return ret;
@@ -927,39 +931,39 @@ static int video_takepict_start(FAR struct video_mng_s *vmng,
     }
   else
     {
-    if (capture_num > 0)
+      if (capture_num > 0)
         {
          vmng->still_inf.remaining_capnum = capture_num;
         }
-    else
+      else
         {
          vmng->still_inf.remaining_capnum = VIDEO_REMAINING_CAPNUM_INFINITY;
         }
 
-    /* Control video stream prior to still stream */
+      /* Control video stream prior to still stream */
 
-    flags = enter_critical_section();
+      flags = enter_critical_section();
 
-    next_video_state = estimate_next_video_state(vmng,
-                                               CAUSE_STILL_START);
-    change_video_state(vmng, next_video_state);
+      next_video_state = estimate_next_video_state(vmng,
+                                                   CAUSE_STILL_START);
+      change_video_state(vmng, next_video_state);
 
-    leave_critical_section(flags);
+      leave_critical_section(flags);
 
-    dma_container = video_framebuff_get_dma_container
-                             (&vmng->still_inf.bufinf);
-    if (dma_container)
+      dma_container = video_framebuff_get_dma_container
+                       (&vmng->still_inf.bufinf);
+      if (dma_container)
         {
-         /* Start video stream DMA */
+          /* Start video stream DMA */
 
-         g_video_devops->set_buftype(V4L2_BUF_TYPE_STILL_CAPTURE);
-         g_video_devops->set_buf(dma_container->buf.m.userptr,
-                              dma_container->buf.length);
-         vmng->still_inf.state = VIDEO_STATE_DMA;
+          g_video_devops->set_buftype(V4L2_BUF_TYPE_STILL_CAPTURE);
+          g_video_devops->set_buf(dma_container->buf.m.userptr,
+                                  dma_container->buf.length);
+          vmng->still_inf.state = VIDEO_STATE_DMA;
         }
-    else
+      else
         {
-         vmng->still_inf.state = VIDEO_STATE_STREAMON;
+          vmng->still_inf.state = VIDEO_STATE_STREAMON;
         }
     }
 
@@ -993,6 +997,7 @@ static int video_takepict_stop(FAR struct video_mng_s *vmng, bool halfpush)
         {
           g_video_devops->cancel_dma();
         }
+
       leave_critical_section(flags);
 
       vmng->still_inf.state = VIDEO_STATE_STREAMOFF;
@@ -1431,6 +1436,7 @@ static FAR void *video_register(FAR const char *devpath)
       kmm_free(priv);
       return NULL;
     }
+
   memcpy(priv->devpath, devpath, allocsize);
   priv->devpath[allocsize] = '\0';
 
@@ -1476,7 +1482,6 @@ static int video_unregister(FAR video_mng_t *v_mgr)
 /****************************************************************************
  * Public Functions
  ****************************************************************************/
-static FAR void *video_handler;
 
 int video_initialize(FAR const char *devpath)
 {
@@ -1498,6 +1503,7 @@ int video_uninitialize(void)
     {
       return OK;
     }
+
   video_unregister(video_handler);
 
   is_initialized = false;
diff --git a/drivers/wireless/bluetooth/bt_uart_bcm4343x.c b/drivers/wireless/bluetooth/bt_uart_bcm4343x.c
index fb110f4..1546f0c 100644
--- a/drivers/wireless/bluetooth/bt_uart_bcm4343x.c
+++ b/drivers/wireless/bluetooth/bt_uart_bcm4343x.c
@@ -302,7 +302,9 @@ static int load_bcm4343x_firmware(FAR const struct btuart_lowerhalf_s *lower)
       0x00
     };
 
-  /* Let's temporarily connect to the hci uart rx callback so we can get data */
+  /* Let's temporarily connect to the hci uart rx callback so we can get
+   * data.
+   */
 
   lower->rxattach(lower, hciuart_cb, &rxsem);
   lower->rxenable(lower, true);
diff --git a/drivers/wireless/bluetooth/bt_uart_shim.c b/drivers/wireless/bluetooth/bt_uart_shim.c
index a8e14cd..062b83e 100644
--- a/drivers/wireless/bluetooth/bt_uart_shim.c
+++ b/drivers/wireless/bluetooth/bt_uart_shim.c
@@ -242,7 +242,7 @@ hciuart_setbaud(FAR const struct btuart_lowerhalf_s *lower, uint32_t baud)
   ret = file_ioctl(&state->f, TCGETS, (long unsigned int)&tio);
   if (ret)
     {
-      wlerr("hciuart_setbaud: ERROR during TCGETS\n");
+      wlerr("ERROR during TCGETS\n");
       return ret;
     }
 
@@ -259,7 +259,7 @@ hciuart_setbaud(FAR const struct btuart_lowerhalf_s *lower, uint32_t baud)
 
   if (ret)
     {
-      wlerr("hciuart_setbaud: ERROR during TCSETS, does UART support CTS/RTS?\n");
+      wlerr("ERROR during TCSETS, does UART support CTS/RTS?\n");
       return ret;
     }
 
@@ -286,10 +286,11 @@ hciuart_read(FAR const struct btuart_lowerhalf_s *lower,
   FAR struct hciuart_state_s *state = &config->state;
   size_t ntotal;
 
-  wlinfo("config %p buffer %p buflen %lu\n", config, buffer, (size_t) buflen);
+  wlinfo("config %p buffer %p buflen %lu\n",
+         config, buffer, (size_t) buflen);
 
-  /* NOTE: This assumes that the caller has exclusive access to the Rx buffer,
-   * i.e., one lower half instance can server only one upper half!
+  /* NOTE: This assumes that the caller has exclusive access to the Rx
+   * buffer, i.e., one lower half instance can server only one upper half!
    */
 
   ntotal = file_read(&state->f, buffer, buflen);
@@ -318,7 +319,8 @@ hciuart_write(FAR const struct btuart_lowerhalf_s *lower,
     = (FAR const struct hciuart_config_s *)lower;
   FAR const struct hciuart_state_s *state = &config->state;
 
-  wlinfo("config %p buffer %p buflen %lu\n", config, buffer, (size_t) buflen);
+  wlinfo("config %p buffer %p buflen %lu\n",
+         config, buffer, (size_t) buflen);
 
   buflen = file_write((struct file *)&state->f, buffer, buflen);
 
@@ -367,7 +369,9 @@ static int hcicollecttask(int argc, FAR char **argv)
           continue;
         }
 
-      /* These flags can change dynamically as new events occur, so snapshot */
+      /* These flags can change dynamically as new events occur, so
+       * snapshot.
+       */
 
       irqstate_t flags = enter_critical_section();
       uint32_t tevents = s->p.revents;
@@ -434,7 +438,8 @@ FAR void *bt_uart_shim_getdevice(FAR char *path)
 
   /* Get the memory for this shim instance */
 
-  g_n = (struct hciuart_config_s *)kmm_zalloc(sizeof(struct hciuart_config_s));
+  g_n = (FAR struct hciuart_config_s *)
+    kmm_zalloc(sizeof(struct hciuart_config_s));
 
   if (!g_n)
     {
diff --git a/drivers/wireless/ieee80211/bcm43xxx/bcmf_driver.c b/drivers/wireless/ieee80211/bcm43xxx/bcmf_driver.c
index b96922a..4560ab7 100644
--- a/drivers/wireless/ieee80211/bcm43xxx/bcmf_driver.c
+++ b/drivers/wireless/ieee80211/bcm43xxx/bcmf_driver.c
@@ -73,9 +73,9 @@
 #define BCMF_SCAN_RESULT_SIZE  1024
 
 /* CLM file is cut into pieces of MAX_CHUNK_LEN.
- * It is relatively small because dongles (FW) have a small maximum size input
- * payload restriction for ioctl's ... something like 1900'ish bytes. So chunk
- * len should not exceed 1400 bytes
+ * It is relatively small because dongles (FW) have a small maximum size
+ * input payload restriction for ioctl's ... something like 1900'ish bytes.
+ * So chunk len should not exceed 1400 bytes
  *
  * NOTE:  CONFIG_NET_ETH_PKTSIZE is the MTU plus the size of the Ethernet
  * header (14 bytes).
@@ -198,7 +198,8 @@ FAR struct bcmf_dev_s *bcmf_allocate_device(void)
       goto exit_free_priv;
     }
 
-  if ((ret = nxsem_set_protocol(&priv->control_timeout, SEM_PRIO_NONE)) != OK)
+  if ((ret = nxsem_set_protocol(&priv->control_timeout, SEM_PRIO_NONE)) !=
+      OK)
     {
       goto exit_free_priv;
     }
@@ -324,7 +325,8 @@ int bcmf_driver_download_clm(FAR struct bcmf_dev_s *priv)
       /* CLM header */
 
       dlhead             = (struct wl_dload_data *)downloadbuff;
-      dlhead->flag       = (DLOAD_HANDLER_VER << DLOAD_FLAG_VER_SHIFT) | dl_flag;
+      dlhead->flag       = (DLOAD_HANDLER_VER << DLOAD_FLAG_VER_SHIFT) |
+                           dl_flag;
       dlhead->dload_type = DL_TYPE_CLM;
       dlhead->len        = chunk_len;
       dlhead->crc        = 0;
@@ -389,7 +391,8 @@ int bcmf_driver_download_clm(FAR struct bcmf_dev_s *priv)
       uint32_t out_len;
 
       chunk_len = datalen >= MAX_CHUNK_LEN ? MAX_CHUNK_LEN : datalen;
-      memcpy(downloadbuff + sizeof(struct wl_dload_data), srcbuff, chunk_len);
+      memcpy(downloadbuff + sizeof(struct wl_dload_data), srcbuff,
+             chunk_len);
       datalen  -= chunk_len;
       srcbuff  += chunk_len;
 
@@ -401,7 +404,8 @@ int bcmf_driver_download_clm(FAR struct bcmf_dev_s *priv)
       /* CLM header */
 
       dlhead             = (struct wl_dload_data *)downloadbuff;
-      dlhead->flag       = (DLOAD_HANDLER_VER << DLOAD_FLAG_VER_SHIFT) | dl_flag;
+      dlhead->flag       = (DLOAD_HANDLER_VER << DLOAD_FLAG_VER_SHIFT) |
+                           dl_flag;
       dlhead->dload_type = DL_TYPE_CLM;
       dlhead->len        = chunk_len;
       dlhead->crc        = 0;
@@ -537,16 +541,26 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv)
 
   /*  Register authentication related events */
 
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_ASSOC_IND_NDIS);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_AUTH);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_ASSOC);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_LINK);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_PSK_SUP);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_JOIN);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_SET_SSID);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_DEAUTH_IND);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_DISASSOC);
-  bcmf_event_register(priv, bcmf_wl_auth_event_handler, WLC_E_DISASSOC_IND);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_ASSOC_IND_NDIS);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_AUTH);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_ASSOC);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_LINK);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_PSK_SUP);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_JOIN);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_SET_SSID);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_DEAUTH_IND);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_DISASSOC);
+  bcmf_event_register(priv, bcmf_wl_auth_event_handler,
+                      WLC_E_DISASSOC_IND);
 
   if (bcmf_event_push_config(priv))
     {
@@ -559,19 +573,22 @@ int bcmf_driver_initialize(FAR struct bcmf_dev_s *priv)
 }
 
 void bcmf_wl_default_event_handler(FAR struct bcmf_dev_s *priv,
-                                   struct bcmf_event_s *event, unsigned int len)
+                                   struct bcmf_event_s *event,
+                                   unsigned int len)
 {
   wlinfo("Got event %d from <%s>\n", bcmf_getle32(&event->type),
                                      event->src_name);
 }
 
 void bcmf_wl_radio_event_handler(FAR struct bcmf_dev_s *priv,
-                                 struct bcmf_event_s *event, unsigned int len)
+                                 struct bcmf_event_s *event,
+                                 unsigned int len)
 {
 }
 
 void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv,
-                                   struct bcmf_event_s *event, unsigned int len)
+                                struct bcmf_event_s *event,
+                                unsigned int len)
 {
   uint32_t type;
   uint32_t status;
@@ -598,7 +615,8 @@ void bcmf_wl_auth_event_handler(FAR struct bcmf_dev_s *priv,
  */
 
 void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv,
-                                   struct bcmf_event_s *event, unsigned int len)
+                                struct bcmf_event_s *event,
+                                unsigned int len)
 {
   uint32_t status;
   uint32_t event_len;
@@ -642,7 +660,8 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv,
 
   result = (struct wl_escan_result *)&event[1];
 
-  if (len < result->buflen || result->buflen < sizeof(struct wl_escan_result))
+  if (len < result->buflen ||
+      result->buflen < sizeof(struct wl_escan_result))
     {
       goto exit_invalid_frame;
     }
@@ -690,7 +709,8 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv,
 
           if (iwe->cmd == SIOCGIWAP)
             {
-              if (memcmp(&iwe->u.ap_addr.sa_data, bss->BSSID.ether_addr_octet,
+              if (memcmp(&iwe->u.ap_addr.sa_data,
+                         bss->BSSID.ether_addr_octet,
                          sizeof(bss->BSSID.ether_addr_octet)) == 0)
                 {
                   goto process_next_bss;
@@ -700,10 +720,14 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv,
           check_offset += iwe->len;
         }
 
-      wlinfo("Scan result: <%.32s> %02x:%02x:%02x:%02x:%02x:%02x\n", bss->SSID,
-               bss->BSSID.ether_addr_octet[0], bss->BSSID.ether_addr_octet[1],
-               bss->BSSID.ether_addr_octet[2], bss->BSSID.ether_addr_octet[3],
-               bss->BSSID.ether_addr_octet[4], bss->BSSID.ether_addr_octet[5]);
+      wlinfo("Scan result: <%.32s> %02x:%02x:%02x:%02x:%02x:%02x\n",
+               bss->SSID,
+               bss->BSSID.ether_addr_octet[0],
+               bss->BSSID.ether_addr_octet[1],
+               bss->BSSID.ether_addr_octet[2],
+               bss->BSSID.ether_addr_octet[3],
+               bss->BSSID.ether_addr_octet[4],
+               bss->BSSID.ether_addr_octet[5]);
 
       /* Copy BSSID */
 
@@ -849,22 +873,28 @@ void bcmf_wl_scan_event_handler(FAR struct bcmf_dev_s *priv,
                   ie_frame_size_aligned = (ie_frame_size + 3) & -4;
 
                   wlinfo("found RSN\n");
-                  if (result_size < BCMF_IW_EVENT_SIZE(data) + ie_frame_size_aligned)
+
+                  if (result_size < BCMF_IW_EVENT_SIZE(data) +
+                                    ie_frame_size_aligned)
                     {
                       break;
                     }
 
-                  iwe = (struct iw_event *)&priv->scan_result[priv->scan_result_size];
+                  iwe = (struct iw_event *)
+                    &priv->scan_result[priv->scan_result_size];
+
                   iwe->len = BCMF_IW_EVENT_SIZE(data)+ie_frame_size_aligned;
                   iwe->cmd = IWEVGENIE;
                   iwe->u.data.flags = 0;
                   iwe->u.data.length = ie_frame_size;
                   iwe->u.data.pointer = (FAR void *)sizeof(iwe->u.data);
-                  memcpy(&iwe->u.data + 1, &ie_buffer[ie_offset], ie_frame_size);
+                  memcpy(&iwe->u.data + 1, &ie_buffer[ie_offset],
+                         ie_frame_size);
 
                   priv->scan_result_size += BCMF_IW_EVENT_SIZE(essid) +
                                             ie_frame_size_aligned;
-                  result_size -= BCMF_IW_EVENT_SIZE(essid) + ie_frame_size_aligned;
+                  result_size -= BCMF_IW_EVENT_SIZE(essid) +
+                                 ie_frame_size_aligned;
                   break;
                 }
 
@@ -1302,7 +1332,8 @@ int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr)
 
           out_len = 4;
           if (bcmf_cdc_ioctl(priv, interface, true,
-                             WLC_SET_WSEC, (uint8_t *)&cipher_mode, &out_len))
+                             WLC_SET_WSEC, (uint8_t *)&cipher_mode,
+                             &out_len))
             {
               return -EIO;
             }
@@ -1311,7 +1342,8 @@ int bcmf_wl_set_auth_param(FAR struct bcmf_dev_s *priv, struct iwreq *iwr)
 
           out_len = 4;
           if (bcmf_cdc_ioctl(priv, interface, true,
-                             WLC_SET_AUTH, (uint8_t *)&wep_auth, &out_len))
+                             WLC_SET_AUTH, (uint8_t *)&wep_auth,
+                             &out_len))
             {
               return -EIO;
             }
diff --git a/drivers/wireless/ieee80211/bcm43xxx/bcmf_sdio.c b/drivers/wireless/ieee80211/bcm43xxx/bcmf_sdio.c
index df9ba5d..2bc960e 100644
--- a/drivers/wireless/ieee80211/bcm43xxx/bcmf_sdio.c
+++ b/drivers/wireless/ieee80211/bcm43xxx/bcmf_sdio.c
@@ -108,7 +108,8 @@ static int  bcmf_chipinitialize(FAR struct bcmf_sdio_dev_s *sbus);
 
 static int  bcmf_oob_irq(FAR void *arg);
 
-static int  bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus, bool sleep);
+static int  bcmf_sdio_bus_sleep(FAR struct bcmf_sdio_dev_s *sbus,
+                                bool sleep);
 
 static void bcmf_sdio_waitdog_timeout(int argc, wdparm_t arg1, ...);
 static int  bcmf_sdio_thread(int argc, char **argv);
@@ -605,8 +606,8 @@ int bcmf_transfer_bytes(FAR struct bcmf_sdio_dev_s *sbus, bool write,
       nblocks = 0;
     }
 
-  return sdio_io_rw_extended(sbus->sdio_dev, write,
-                             function, address, true, buf, blocklen, nblocks);
+  return sdio_io_rw_extended(sbus->sdio_dev, write, function, address, true,
+                             buf, blocklen, nblocks);
 }
 
 /****************************************************************************
@@ -876,15 +877,17 @@ int bcmf_sdio_thread(int argc, char **argv)
 
           sbus->irq_pending = false;
 
-          bcmf_read_sbregw(sbus,
-                          CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
-                          intstatus), &sbus->intstatus);
+          bcmf_read_sbregw(
+            sbus,
+            CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID], intstatus),
+            &sbus->intstatus);
 
           /* Clear interrupts */
 
-          bcmf_write_sbregw(sbus,
-                            CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID],
-                            intstatus), sbus->intstatus);
+          bcmf_write_sbregw(
+            sbus,
+            CORE_BUS_REG(sbus->chip->core_base[SDIOD_CORE_ID], intstatus),
+            sbus->intstatus);
         }
 
       /* On frame indication, read available frames */
diff --git a/drivers/wireless/ieee802154/xbee/xbee.c b/drivers/wireless/ieee802154/xbee/xbee.c
index cef7f3a..327addd 100644
--- a/drivers/wireless/ieee802154/xbee/xbee.c
+++ b/drivers/wireless/ieee802154/xbee/xbee.c
@@ -78,8 +78,8 @@ static bool xbee_validate_apiframe(uint8_t frametype, uint16_t framelen);
 static bool xbee_verify_checksum(FAR const struct iob_s *iob);
 static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
               FAR struct iob_s *iob);
-static void xbee_process_txstatus(FAR struct xbee_priv_s *priv, uint8_t frameid,
-              uint8_t status);
+static void xbee_process_txstatus(FAR struct xbee_priv_s *priv,
+              uint8_t frameid, uint8_t status);
 static void xbee_process_rxframe(FAR struct xbee_priv_s *priv,
               FAR struct iob_s *frame,
               enum ieee802154_addrmode_e addrmode);
@@ -152,8 +152,8 @@ static int xbee_interrupt(int irq, FAR void *context, FAR void *arg)
  * Name: xbee_attnworker
  *
  * Description:
- *   Perform interrupt handling (Attention) logic outside of the interrupt handler
- *   (on the work queue thread).
+ *   Perform interrupt handling (Attention) logic outside of the interrupt
+ *   handler (on the work queue thread).
  *
  * Input Parameters:
  *   arg     - The reference to the driver structure (cast to void*)
@@ -247,12 +247,16 @@ static void xbee_attnworker(FAR void *arg)
                 break;
               case XBEE_APIFRAMEINDEX_TYPE:
                 {
-                  /* Check that the length and frame type make sense together */
+                  /* Check that the length and frame type make sense
+                   * together.
+                   */
 
                   if (!xbee_validate_apiframe(iob->io_data[iob->io_len],
-                                              rxframelen - XBEE_APIFRAME_OVERHEAD))
+                                              rxframelen -
+                                              XBEE_APIFRAME_OVERHEAD))
                     {
-                      wlwarn("invalid length on incoming API frame. Dropping!\n");
+                      wlwarn("invalid length on incoming API frame. "
+                             "Dropping!\n");
                       iob->io_len = 0;
                     }
                   else
@@ -289,7 +293,8 @@ static void xbee_attnworker(FAR void *arg)
                        }
                       else
                         {
-                          wlwarn("invalid checksum on incoming API frame. Dropping!\n");
+                          wlwarn("invalid checksum on incoming API frame. "
+                                 "Dropping!\n");
                           iob->io_len = 0;
                         }
                     }
@@ -308,12 +313,12 @@ static void xbee_attnworker(FAR void *arg)
         }
     }
 
-  /* The last IOB in the list (or the only one) may be able to be freed since
-   * it may not have any valid data. If it contains some data, but not a whole
-   * API frame, something is wrong, so we just warn the user and drop the
-   * data.  If the data was valid, the ATTN line should have stayed asserted
-   * until all the data was clocked in. So if we don't have a full frame,
-   * we can only drop it.
+  /* The last IOB in the list (or the only one) may be able to be freed
+   * since it may not have any valid data. If it contains some data, but not
+   * a whole API frame, something is wrong, so we just warn the user and
+   * drop the data.  If the data was valid, the ATTN line should have stayed
+   * asserted until all the data was clocked in. So if we don't have a full
+   * frame, we can only drop it.
    */
 
   if (iob != NULL)
@@ -364,8 +369,8 @@ static void xbee_attnworker(FAR void *arg)
 
   /* Before unlocking the SPI bus, we "detach" the IOB list from the private
    * struct and keep a copy. When the SPI bus becomes free, more data can
-   * be clocked in from an SPI write. By detaching the IOB list, we can process
-   * the incoming data without holding up the SPI bus
+   * be clocked in from an SPI write. By detaching the IOB list, we can
+   * process the incoming data without holding up the SPI bus
    */
 
   iobhead = priv->rx_apiframes;
@@ -392,7 +397,8 @@ static void xbee_attnworker(FAR void *arg)
 
   if (priv->attn_latched)
     {
-      work_queue(HPWORK, &priv->attnwork, xbee_attnworker, (FAR void *)priv, 0);
+      work_queue(HPWORK, &priv->attnwork, xbee_attnworker,
+                 (FAR void *)priv, 0);
     }
 }
 
@@ -537,9 +543,9 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
   while (frame)
     {
 #ifdef CONFIG_XBEE_LOCKUP_WORKAROUND
-      /* Any time we receive an API frame from the XBee we reschedule our lockup
-       * timeout. Receiving an API frame is an indication that the XBee is not
-       * locked up.
+      /* Any time we receive an API frame from the XBee we reschedule our
+       * lockup timeout. Receiving an API frame is an indication that the
+       * XBee is not locked up.
        */
 
       xbee_lockupcheck_reschedule(priv);
@@ -554,24 +560,25 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
           case XBEE_APIFRAME_MODEMSTATUS:
             {
 #ifdef CONFIG_XBEE_LOCKUP_WORKAROUND
-              /* If the Modem Status indicates that the coordinator has just formed
-               * a new network, we know that the channel and PAN ID are locked in.
-               * In case we need to reset the radio due to a lockup, we tell the
-               * XBee to write the parameters to non-volatile memory so that upon
-               * reset, we can resume operation
+              /* If the Modem Status indicates that the coordinator has just
+               * formed a new network, we know that the channel and PAN ID
+               * are locked in.  In case we need to reset the radio due to a
+               * lockup, we tell the XBee to write the parameters to non-
+               * volatile memory so that upon reset, we can resume operation.
                */
 
               if (frame->io_data[frame->io_offset] == 0x06)
                 {
                   if (work_available(&priv->backupwork))
                     {
-                      work_queue(LPWORK, &priv->backupwork, xbee_backup_worker,
-                                 (FAR void *)priv, 0);
+                      work_queue(LPWORK, &priv->backupwork,
+                                 xbee_backup_worker, (FAR void *)priv, 0);
                     }
                 }
 #endif
 
-              wlinfo("Modem Status: %d\n", frame->io_data[frame->io_offset++]);
+              wlinfo("Modem Status: %d\n",
+                     frame->io_data[frame->io_offset++]);
             }
             break;
 
@@ -597,27 +604,39 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
 
                   if (memcmp(command, "ID", 2) == 0)
                     {
-                      priv->addr.panid[1] = frame->io_data[frame->io_offset++];
-                      priv->addr.panid[0] = frame->io_data[frame->io_offset++];
+                      priv->addr.panid[1] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.panid[0] =
+                        frame->io_data[frame->io_offset++];
                     }
                   else if (memcmp(command, "SH", 2) == 0)
                     {
-                      priv->addr.eaddr[7] = frame->io_data[frame->io_offset++];
-                      priv->addr.eaddr[6] = frame->io_data[frame->io_offset++];
-                      priv->addr.eaddr[5] = frame->io_data[frame->io_offset++];
-                      priv->addr.eaddr[4] = frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[7] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[6] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[5] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[4] =
+                        frame->io_data[frame->io_offset++];
                     }
                   else if (memcmp(command, "SL", 2) == 0)
                     {
-                      priv->addr.eaddr[3] = frame->io_data[frame->io_offset++];
-                      priv->addr.eaddr[2] = frame->io_data[frame->io_offset++];
-                      priv->addr.eaddr[1] = frame->io_data[frame->io_offset++];
-                      priv->addr.eaddr[0] = frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[3] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[2] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[1] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.eaddr[0] =
+                        frame->io_data[frame->io_offset++];
                     }
                   else if (memcmp(command, "MY", 2) == 0)
                     {
-                      priv->addr.saddr[1] = frame->io_data[frame->io_offset++];
-                      priv->addr.saddr[0] = frame->io_data[frame->io_offset++];
+                      priv->addr.saddr[1] =
+                        frame->io_data[frame->io_offset++];
+                      priv->addr.saddr[0] =
+                        frame->io_data[frame->io_offset++];
                     }
                   else if (memcmp(command, "CH", 2) == 0)
                     {
@@ -625,15 +644,17 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
                     }
                   else if (memcmp(command, "VR", 2) == 0)
                     {
-                      priv->firmwareversion = frame->io_data[frame->io_offset++] << 8;
-                      priv->firmwareversion |= frame->io_data[frame->io_offset++];
+                      priv->firmwareversion  =
+                        frame->io_data[frame->io_offset++] << 8;
+                      priv->firmwareversion |=
+                        frame->io_data[frame->io_offset++];
                     }
                   else if (memcmp(command, "AI", 2) == 0)
                     {
                       wlinfo("Association Indication: %d\n",
                              frame->io_data[frame->io_offset]);
 
-                      /* 0xff = No assocication status determined yet. */
+                      /* 0xff = No association status determined yet. */
 
                       if (frame->io_data[frame->io_offset] != 0xff &&
                           frame->io_data[frame->io_offset] != 0x13)
@@ -649,18 +670,19 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
                               primitive->u.assocconf.status =
                                 IEEE802154_STATUS_SUCCESS;
 #ifdef CONFIG_XBEE_LOCKUP_WORKAROUND
-                              /* Upon successful association, we know that the
-                               * channel and PAN ID give us a valid connection.
-                               * In case we need to reset the radio due to a lockup,
-                               * we tell the XBee to write the parameters to
-                               * non-volatile memory so that upon reset, we can
-                               * resume operation
+                              /* Upon successful association, we know that
+                               * the channel and PAN ID give us a valid
+                               * connection.  In case we need to reset the
+                               * radio due to a lockup, we tell the XBee to
+                               * write the parameters to non-volatile memory
+                               * so that upon reset, we can resume operation.
                                */
 
                               if (work_available(&priv->backupwork))
                                 {
                                   work_queue(LPWORK, &priv->backupwork,
-                                             xbee_backup_worker, (FAR void *)priv, 0);
+                                             xbee_backup_worker,
+                                             (FAR void *)priv, 0);
                                 }
 #endif
                             }
@@ -749,11 +771,12 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
             {
               nextframe = frame->io_flink;
               frame->io_flink = NULL;
-              xbee_process_rxframe(priv, frame, IEEE802154_ADDRMODE_EXTENDED);
+              xbee_process_rxframe(priv, frame,
+                                   IEEE802154_ADDRMODE_EXTENDED);
               frame = nextframe;
 
-              /* xbee_process_rxframe takes care of freeing the IOB or passing
-               * it along to the next highest layer.
+              /* xbee_process_rxframe takes care of freeing the IOB or
+               * passing it along to the next highest layer.
                */
 
               continue;
@@ -767,8 +790,8 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
               xbee_process_rxframe(priv, frame, IEEE802154_ADDRMODE_SHORT);
               frame = nextframe;
 
-              /* xbee_process_rxframe takes care of freeing the IOB or passing
-               * it along to the next highest layer.
+              /* xbee_process_rxframe takes care of freeing the IOB or
+               * passing it along to the next highest layer.
                */
 
               continue;
@@ -777,20 +800,21 @@ static void xbee_process_apiframes(FAR struct xbee_priv_s *priv,
 
           default:
             {
-              /* This really should never happen since xbee_validateframe should
-               * have caught it.
+              /* This really should never happen since xbee_validateframe
+               * should have caught it.
                */
 
-              wlwarn("Unknown frame type: %d\n", frame[XBEE_APIFRAMEINDEX_TYPE]);
+              wlwarn("Unknown frame type: %d\n",
+                     frame[XBEE_APIFRAMEINDEX_TYPE]);
             }
             break;
         }
 
       /* IOB free logic assumes that a valid io_flink entry in the IOB that
-       * is being freed indicates that the IOB is a part of an IOB chain. Since
-       * that is not the case here and we are just using the io_flink field
-       * as a way of managing a list of independent frames, we set the io_flink
-       * to NULL prior to freeing it.
+       * is being freed indicates that the IOB is a part of an IOB chain.
+       * Since that is not the case here and we are just using the io_flink
+       * field as a way of managing a list of independent frames, we set the
+       * io_flink to NULL prior to freeing it.
        */
 
       nextframe = frame->io_flink;
@@ -844,10 +868,10 @@ static void xbee_process_rxframe(FAR struct xbee_priv_s *priv,
       dataind->src.saddr[0] = frame->io_data[frame->io_offset++];
     }
 
-  /* The XBee does not give us information about how the device was addressed.
-   * It only indicates the source mode. Therefore, we make the assumption that
-   * if the saddr is set, we we're addressed using the saddr, otherwise we must
-   * have been addressed using the eaddr.
+  /* The XBee does not give us information about how the device was
+   * addressed.  It only indicates the source mode. Therefore, we make the
+   * assumption that if the saddr is set, we we're addressed using the
+   * saddr, otherwise we must have been addressed using the eaddr.
    */
 
   memcpy(&dataind->dest, &priv->addr, sizeof(struct ieee802154_addr_s));
@@ -882,8 +906,8 @@ static void xbee_process_rxframe(FAR struct xbee_priv_s *priv,
  *
  ****************************************************************************/
 
-static void xbee_process_txstatus(FAR struct xbee_priv_s *priv, uint8_t frameid,
-                                  uint8_t status)
+static void xbee_process_txstatus(FAR struct xbee_priv_s *priv,
+                                  uint8_t frameid, uint8_t status)
 {
   FAR struct ieee802154_primitive_s *primitive;
 
@@ -894,17 +918,24 @@ static void xbee_process_txstatus(FAR struct xbee_priv_s *priv, uint8_t frameid,
   switch (status)
     {
       case 0x00:
-        primitive->u.dataconf.status = IEEE802154_STATUS_SUCCESS;
+        primitive->u.dataconf.status =
+          IEEE802154_STATUS_SUCCESS;
         break;
+
       case 0x01:
       case 0x21:
-        primitive->u.dataconf.status = IEEE802154_STATUS_NO_ACK;
+        primitive->u.dataconf.status =
+          IEEE802154_STATUS_NO_ACK;
         break;
+
       case 0x02:
-        primitive->u.dataconf.status = IEEE802154_STATUS_CHANNEL_ACCESS_FAILURE;
+        primitive->u.dataconf.status =
+          IEEE802154_STATUS_CHANNEL_ACCESS_FAILURE;
         break;
+
       default:
-        primitive->u.dataconf.status = IEEE802154_STATUS_FAILURE;
+        primitive->u.dataconf.status =
+          IEEE802154_STATUS_FAILURE;
         break;
     }
 
@@ -919,8 +950,8 @@ static void xbee_process_txstatus(FAR struct xbee_priv_s *priv, uint8_t frameid,
 
   xbee_notify(priv, primitive);
 
-  /* If this is the frame we are currently waiting on, cancel the timeout, and
-   * notify the waiting thread that the transmit is done
+  /* If this is the frame we are currently waiting on, cancel the timeout,
+   * and notify the waiting thread that the transmit is done
    */
 
   if (priv->frameid == frameid)
@@ -983,11 +1014,12 @@ static void xbee_notify_worker(FAR void *arg)
 
   while (primitive != NULL)
     {
-      /* Data indications are a special case since the frame can only be passed to
-       * one place. The return value of the notify call is used to accept or reject
-       * the primitive. In the case of the data indication, there can only be one
-       * accept. Callbacks are stored in order of there receiver priority ordered
-       * when the callbacks are bound in mac802154_bind().
+      /* Data indications are a special case since the frame can only be
+       * passed to one place. The return value of the notify call is used to
+       * accept or reject the primitive. In the case of the data indication,
+       * there can only be one accept. Callbacks are stored in order of
+       * there receiver priority ordered when the callbacks are bound in
+       * mac802154_bind().
        */
 
       if (primitive->type == IEEE802154_PRIMITIVE_IND_DATA)
@@ -1003,8 +1035,8 @@ static void xbee_notify_worker(FAR void *arg)
                   ret = cb->notify(cb, primitive);
                   if (ret >= 0)
                     {
-                      /* The receiver accepted and disposed of the frame and it's
-                       * meta-data. We are done.
+                      /* The receiver accepted and disposed of the frame and
+                       * it's meta-data.  We are done.
                        */
 
                       dispose = false;
@@ -1022,8 +1054,8 @@ static void xbee_notify_worker(FAR void *arg)
         }
       else
         {
-          /* Set the number of clients count so that the primitive resources will be
-           * preserved until all clients are finished with it.
+          /* Set the number of clients count so that the primitive resources
+           * will be preserved until all clients are finished with it.
            */
 
           primitive->nclients = priv->nclients;
@@ -1050,8 +1082,9 @@ static void xbee_notify_worker(FAR void *arg)
       /* Get the next primitive then loop */
 
       while (nxsem_wait(&priv->primitive_sem) < 0);
-      primitive =
-        (FAR struct ieee802154_primitive_s *)sq_remfirst(&priv->primitive_queue);
+
+      primitive = (FAR struct ieee802154_primitive_s *)
+                  sq_remfirst(&priv->primitive_queue);
       nxsem_post(&priv->primitive_sem);
     }
 }
@@ -1093,8 +1126,9 @@ static void xbee_atquery_timeout(int argc, uint32_t arg, ...)
  * Name: xbee_lockupcheck_timeout
  *
  * Description:
- *   This function runs when a query to the XBee has not been issued for awhile.
- *   We query periodically in an effort to detect if the XBee has locked up.
+ *   This function runs when a query to the XBee has not been issued for
+ *   awhile.  We query periodically in an effort to detect if the XBee has
+ *   locked up.
  *
  * Input Parameters:
  *   argc - The number of available arguments
@@ -1127,10 +1161,10 @@ static void xbee_lockupcheck_timeout(int argc, uint32_t arg, ...)
  *    Perform an AT query to make sure the XBee is still responsive. If we've
  *    gotten here, it means we haven't talked to the XBee in a while. This
  *    is to workaround an issue where the XBee locks up. In this condition,
- *    most of the time, querying it kicks it out of the state. In some conditions
- *    though, the XBee locks up to the point where it needs to be reset. This
- *    will be handled inside xbee_atquery; if we don't get a response we will
- *    reset the XBee.
+ *    most of the time, querying it kicks it out of the state. In some
+ *    conditions though, the XBee locks up to the point where it needs to be
+ *    reset.  This will be handled inside xbee_atquery; if we don't get a
+ *    response we will reset the XBee.
  *
  ****************************************************************************/
 
@@ -1170,10 +1204,11 @@ static void xbee_lockupcheck_reschedule(FAR struct xbee_priv_s *priv)
 {
   wd_cancel(priv->lockup_wd);
 
-  /* Kickoff the watchdog timer that will query the XBee periodically (if naturally
-   * occurring queries do not occur). We query periodically to make sure the XBee
-   * is still responsive. If during any query, the XBee does not respond after
-   * multiple attempts, we restart the XBee to get it back in a working state
+  /* Kickoff the watchdog timer that will query the XBee periodically (if
+   * naturally occurring queries do not occur). We query periodically to
+   * make sure the XBee is still responsive. If during any query, the XBee
+   * does not respond after multiple attempts, we restart the XBee to get
+   * it back in a working state
    */
 
   wd_start(priv->lockup_wd, XBEE_LOCKUP_QUERYTIME, xbee_lockupcheck_timeout,
@@ -1311,9 +1346,11 @@ void xbee_send_apiframe(FAR struct xbee_priv_s *priv,
 
   /* Allocate an IOB for the incoming data. The XBee supports full-duplex
    * SPI communication. This means that the MISO data can become valid at any
-   * time. This requires us to process incoming MISO data to see if it is valid.
+   * time. This requires us to process incoming MISO data to see if it is
+   * valid.
    *
-   * If we can't allocate an IOB, then we have to just drop the incoming data.
+   * If we can't allocate an IOB, then we have to just drop the incoming
+   * data.
    */
 
   iob             = iob_tryalloc(false, IOBUSER_WIRELESS_RAD802154);
@@ -1323,8 +1360,8 @@ void xbee_send_apiframe(FAR struct xbee_priv_s *priv,
   iob->io_pktlen  = 0;
 
   /* Keep a reference to the first IOB.  If we need to allocate more than
-   * one to hold each API frame, then we will still have this reference to the
-   * head of the list
+   * one to hold each API frame, then we will still have this reference to
+   * the head of the list
    */
 
   iobhead = iob;
@@ -1379,12 +1416,16 @@ void xbee_send_apiframe(FAR struct xbee_priv_s *priv,
                 break;
               case XBEE_APIFRAMEINDEX_TYPE:
                 {
-                  /* Check that the length and frame type make sense together */
+                  /* Check that the length and frame type make sense
+                   * together.
+                   */
 
                   if (!xbee_validate_apiframe(iob->io_data[iob->io_len],
-                                              rxframelen - XBEE_APIFRAME_OVERHEAD))
+                                              rxframelen -
+                                              XBEE_APIFRAME_OVERHEAD))
                     {
-                      wlwarn("invalid length on incoming API frame. Dropping!\n");
+                      wlwarn("invalid length on incoming API frame. "
+                             "Dropping!\n");
                       iob->io_len = 0;
                     }
                   else
@@ -1420,7 +1461,8 @@ void xbee_send_apiframe(FAR struct xbee_priv_s *priv,
                        }
                       else
                         {
-                          wlwarn("invalid checksum on incoming API frame. Dropping!\n");
+                          wlwarn("invalid checksum on incoming API frame. "
+                                 "Dropping!\n");
                           iob->io_len = 0;
                         }
                     }
@@ -1434,12 +1476,12 @@ void xbee_send_apiframe(FAR struct xbee_priv_s *priv,
         }
     }
 
-  /* The last IOB in the list (or the only one) may be able to be freed since
-   * it may not have any valid data. If it contains some data, but not a whole
-   * API frame, something is wrong, so we just warn the user and drop the
-   * data.  If the data was valid, the ATTN line should have stayed asserted
-   * until all the data was clocked in. So if we don't have a full frame,
-   * we can only drop it.
+  /* The last IOB in the list (or the only one) may be able to be freed
+   * since it may not have any valid data. If it contains some data, but not
+   * a whole API frame, something is wrong, so we just warn the user and
+   * drop the data.  If the data was valid, the ATTN line should have stayed
+   * asserted until all the data was clocked in. So if we don't have a full
+   * frame, we can only drop it.
    */
 
   if (iob != NULL)
@@ -1522,8 +1564,8 @@ int xbee_atquery(FAR struct xbee_priv_s *priv, FAR const char *atcommand)
 
   priv->querydone = false;
 
-  /* We reinitialize this every time, in case something gets out of phase with
-   * the timeout and the received response.
+  /* We reinitialize this every time, in case something gets out of phase
+   * with the timeout and the received response.
    */
 
   nxsem_init(&priv->atresp_sem, 0, 0);
@@ -1535,16 +1577,16 @@ int xbee_atquery(FAR struct xbee_priv_s *priv, FAR const char *atcommand)
        * do not send any additional characters to the device until after
        * you receive the OK response.
        *
-       * If we are issuing a WR command, don't set a timeout. We will have to rely
-       * on the XBee getting back to us reliably.
+       * If we are issuing a WR command, don't set a timeout. We will have
+       * to rely on the XBee getting back to us reliably.
        */
 
       if (memcmp(atcommand, "WR", 2) != 0)
         {
           /* Setup a timeout */
 
-          wd_start(priv->atquery_wd, XBEE_ATQUERY_TIMEOUT, xbee_atquery_timeout,
-                   1, (wdparm_t)priv);
+          wd_start(priv->atquery_wd, XBEE_ATQUERY_TIMEOUT,
+                   xbee_atquery_timeout, 1, (wdparm_t)priv);
         }
 
       /* Send the query */
@@ -1589,7 +1631,8 @@ int xbee_atquery(FAR struct xbee_priv_s *priv, FAR const char *atcommand)
  *
  ****************************************************************************/
 
-void xbee_send_atquery(FAR struct xbee_priv_s *priv, FAR const char *atcommand)
+void xbee_send_atquery(FAR struct xbee_priv_s *priv,
+                       FAR const char *atcommand)
 {
   uint8_t frame[8];
 
@@ -1642,8 +1685,8 @@ void xbee_set_panid(FAR struct xbee_priv_s *priv, FAR const uint8_t *panid)
  * Name: xbee_set_saddr
  *
  * Description:
- *   Sends API frame with AT command request in order to set the Short Address
- *   (Source Address (MY)) of the device
+ *   Sends API frame with AT command request in order to set the Short
+ *   Address (Source Address (MY)) of the device
  *
  ****************************************************************************/
 
@@ -1701,8 +1744,8 @@ void xbee_set_chan(FAR struct xbee_priv_s *priv, uint8_t chan)
  * Name: xbee_set_powerlevel
  *
  * Description:
- *   Sends API frame with AT command request in order to set the RF power level
- *   of the device.
+ *   Sends API frame with AT command request in order to set the RF power
+ *   level of the device.
  *
  ****************************************************************************/
 
@@ -1869,7 +1912,8 @@ void xbee_enable_coord(FAR struct xbee_priv_s *priv, bool enable)
  * Name: xbee_regdump
  *
  * Description:
- *   Perform a series of queries updating struct and printing settings to SYSLOG.
+ *   Perform a series of queries updating struct and printing settings to
+ *   SYSLOG.
  *
  ****************************************************************************/
 
diff --git a/drivers/wireless/ieee802154/xbee/xbee_netdev.c b/drivers/wireless/ieee802154/xbee/xbee_netdev.c
index 1f00c03..266bd75 100644
--- a/drivers/wireless/ieee802154/xbee/xbee_netdev.c
+++ b/drivers/wireless/ieee802154/xbee/xbee_netdev.c
@@ -114,7 +114,9 @@
 #  define XBEENET_FRAMELEN IEEE802154_MAX_PHY_PACKET_SIZE
 #endif
 
-/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */
+/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per
+ * second.
+ */
 
 #define TXPOLL_WDDELAY   (1*CLK_TCK)
 
@@ -128,7 +130,8 @@ struct xbeenet_callback_s
 {
   /* This holds the information visible to the MAC layer */
 
-  struct xbee_maccb_s mc_cb;       /* Interface understood by the MAC layer */
+  struct xbee_maccb_s mc_cb;            /* Interface understood by the MAC
+                                         * layer */
   FAR struct xbeenet_driver_s *mc_priv; /* Our priv data */
 };
 
@@ -251,8 +254,10 @@ static struct sixlowpan_reassbuf_s g_iobuffer;
  *
  *    128  112  96   80    64   48   32   16
  *    ---- ---- ---- ----  ---- ---- ---- ----
- *    fe80 0000 0000 0000  0000 00ff fe00 xxxx 2-byte short address IEEE 48-bit MAC
- *    fe80 0000 0000 0000  xxxx xxxx xxxx xxxx 8-byte extended address IEEE EUI-64
+ *    fe80 0000 0000 0000  0000 00ff fe00 xxxx 2-byte short address IEEE
+ *                                             48-bit MAC
+ *    fe80 0000 0000 0000  xxxx xxxx xxxx xxxx 8-byte extended address IEEE
+ *                                             EUI-64
  *
  ****************************************************************************/
 
@@ -285,15 +290,20 @@ static int xbeenet_set_ipaddress(FAR struct net_driver_s *dev)
     }
   else
     {
-      IEEE802154_EADDRCOPY(dev->d_mac.radio.nv_addr, arg.getreq.attrval.mac.eaddr);
+      IEEE802154_EADDRCOPY(dev->d_mac.radio.nv_addr,
+                           arg.getreq.attrval.mac.eaddr);
       dev->d_mac.radio.nv_addrlen = IEEE802154_EADDRSIZE;
 
       /* Set the IP address based on the eaddr */
 
-      dev->d_ipv6addr[4]  = HTONS((uint16_t)eaddr[0] << 8 | (uint16_t)eaddr[1]);
-      dev->d_ipv6addr[5]  = HTONS((uint16_t)eaddr[2] << 8 | (uint16_t)eaddr[3]);
-      dev->d_ipv6addr[6]  = HTONS((uint16_t)eaddr[4] << 8 | (uint16_t)eaddr[5]);
-      dev->d_ipv6addr[7]  = HTONS((uint16_t)eaddr[6] << 8 | (uint16_t)eaddr[7]);
+      dev->d_ipv6addr[4]  = HTONS((uint16_t)eaddr[0] << 8 |
+                                  (uint16_t)eaddr[1]);
+      dev->d_ipv6addr[5]  = HTONS((uint16_t)eaddr[2] << 8 |
+                                  (uint16_t)eaddr[3]);
+      dev->d_ipv6addr[6]  = HTONS((uint16_t)eaddr[4] << 8 |
+                                  (uint16_t)eaddr[5]);
+      dev->d_ipv6addr[7]  = HTONS((uint16_t)eaddr[6] << 8 |
+                                  (uint16_t)eaddr[7]);
 
       /* Invert the U/L bit */
 
@@ -337,7 +347,8 @@ static int xbeenet_set_ipaddress(FAR struct net_driver_s *dev)
       dev->d_ipv6addr[4]  = 0;
       dev->d_ipv6addr[5]  = HTONS(0x00ff);
       dev->d_ipv6addr[6]  = HTONS(0xfe00);
-      dev->d_ipv6addr[7]  = HTONS((uint16_t)saddr[0] << 8 |  (uint16_t)saddr[1]);
+      dev->d_ipv6addr[7]  = HTONS((uint16_t)saddr[0] << 8 |
+                                  (uint16_t)saddr[1]);
       return OK;
     }
 #endif
@@ -352,8 +363,10 @@ static int xbeenet_set_ipaddress(FAR struct net_driver_s *dev)
  *
  *    128  112  96   80    64   48   32   16
  *    ---- ---- ---- ----  ---- ---- ---- ----
- *    fe80 0000 0000 0000  0000 00ff fe00 xxxx 2-byte short address IEEE 48-bit MAC
- *    fe80 0000 0000 0000  xxxx xxxx xxxx xxxx 8-byte extended address IEEE EUI-64
+ *    fe80 0000 0000 0000  0000 00ff fe00 xxxx 2-byte short address IEEE
+ *                                             48-bit MAC
+ *    fe80 0000 0000 0000  xxxx xxxx xxxx xxxx 8-byte extended address IEEE
+ *                                             EUI-64
  *
  ****************************************************************************/
 
@@ -401,15 +414,16 @@ static int xbeenet_notify(FAR struct xbee_maccb_s *maccb,
     }
 
   /* If there is a registered primitive receiver, queue the event and signal
-   * the receiver. Events should be popped from the queue from the application
-   * at a reasonable rate in order for the MAC layer to be able to allocate new
-   * primitives.
+   * the receiver. Events should be popped from the queue from the
+   * application at a reasonable rate in order for the MAC layer to be able
+   * to allocate new primitives.
    */
 
   if (priv->xd_enableevents)
     {
-      /* Get exclusive access to the driver structure.  We don't care about any
-       * signals so if we see one, just go back to trying to get access again
+      /* Get exclusive access to the driver structure.  We don't care about
+       * any signals so if we see one, just go back to trying to get access
+       * again.
        */
 
       while (nxsem_wait(&priv->xd_exclsem) < 0);
@@ -437,8 +451,8 @@ static int xbeenet_notify(FAR struct xbee_maccb_s *maccb,
       return OK;
     }
 
-  /* By returning a negative value, we let the MAC know that we don't want the
-   * primitive and it will free it for us
+  /* By returning a negative value, we let the MAC know that we don't want
+   * the primitive and it will free it for us
    */
 
   return -1;
@@ -567,8 +581,8 @@ static int xbeenet_rxframe(FAR struct xbeenet_driver_s *priv,
 
 static int xbeenet_txpoll_callback(FAR struct net_driver_s *dev)
 {
-  /* If zero is returned, the polling will continue until all connections have
-   * been examined.
+  /* If zero is returned, the polling will continue until all connections
+   * have been examined.
    */
 
   return 0;
@@ -796,7 +810,8 @@ static int xbeenet_ifup(FAR struct net_driver_s *dev)
 
 static int xbeenet_ifdown(FAR struct net_driver_s *dev)
 {
-  FAR struct xbeenet_driver_s *priv = (FAR struct xbeenet_driver_s *)dev->d_private;
+  FAR struct xbeenet_driver_s *priv =
+    (FAR struct xbeenet_driver_s *)dev->d_private;
   irqstate_t flags;
 
   /* Disable interruption */
@@ -807,9 +822,9 @@ static int xbeenet_ifdown(FAR struct net_driver_s *dev)
 
   wd_cancel(priv->xd_txpoll);
 
-  /* TODO: Put the xbee driver in its reset, non-operational state.  This should be
-   * a known configuration that will guarantee the xbeenet_ifup() always
-   * successfully brings the interface back up.
+  /* TODO: Put the xbee driver in its reset, non-operational state.  This
+   * should be a known configuration that will guarantee the xbeenet_ifup()
+   * always successfully brings the interface back up.
    */
 
   /* Mark the device "down" */
@@ -889,7 +904,8 @@ static void xbeenet_txavail_work(FAR void *arg)
 
 static int xbeenet_txavail(FAR struct net_driver_s *dev)
 {
-  FAR struct xbeenet_driver_s *priv = (FAR struct xbeenet_driver_s *)dev->d_private;
+  FAR struct xbeenet_driver_s *priv =
+    (FAR struct xbeenet_driver_s *)dev->d_private;
 
   wlinfo("Available=%u\n", work_available(&priv->xd_pollwork));
 
@@ -902,7 +918,8 @@ static int xbeenet_txavail(FAR struct net_driver_s *dev)
     {
       /* Schedule to serialize the poll on the worker thread. */
 
-      work_queue(XBEENET_WORK, &priv->xd_pollwork, xbeenet_txavail_work, priv, 0);
+      work_queue(XBEENET_WORK, &priv->xd_pollwork, xbeenet_txavail_work,
+                 priv, 0);
     }
 
   return OK;
@@ -927,9 +944,11 @@ static int xbeenet_txavail(FAR struct net_driver_s *dev)
  ****************************************************************************/
 
 #ifdef CONFIG_NET_MCASTGROUP
-static int xbeenet_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
+static int xbeenet_addmac(FAR struct net_driver_s *dev,
+                          FAR const uint8_t *mac)
 {
-  FAR struct xbeenet_driver_s *priv = (FAR struct xbeenet_driver_s *)dev->d_private;
+  FAR struct xbeenet_driver_s *priv =
+    (FAR struct xbeenet_driver_s *)dev->d_private;
 
   /* Add the MAC address to the hardware multicast routing table.  Not used
    * with IEEE 802.15.4 radios.
@@ -943,8 +962,8 @@ static int xbeenet_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
  * Name: xbeenet_rmmac
  *
  * Description:
- *   NuttX Callback: Remove the specified MAC address from the hardware multicast
- *   address filtering
+ *   NuttX Callback: Remove the specified MAC address from the hardware
+ *   multicast address filtering
  *
  * Input Parameters:
  *   dev  - Reference to the NuttX driver state structure
@@ -958,12 +977,14 @@ static int xbeenet_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
  ****************************************************************************/
 
 #ifdef CONFIG_NET_MCASTGROUP
-static int xbeenet_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
+static int xbeenet_rmmac(FAR struct net_driver_s *dev,
+                         FAR const uint8_t *mac)
 {
-  FAR struct xbeenet_driver_s *priv = (FAR struct xbeenet_driver_s *)dev->d_private;
+  FAR struct xbeenet_driver_s *priv =
+    (FAR struct xbeenet_driver_s *)dev->d_private;
 
-  /* Remove the MAC address from the hardware multicast routing table  Not used
-   * with IEEE 802.15.4 radios.
+  /* Remove the MAC address from the hardware multicast routing table.  Not
+   * used with IEEE 802.15.4 radios.
    */
 
   return -ENOSYS;
@@ -992,7 +1013,8 @@ static int xbeenet_rmmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
 static int xbeenet_ioctl(FAR struct net_driver_s *dev, int cmd,
                         unsigned long arg)
 {
-  FAR struct xbeenet_driver_s *priv = (FAR struct xbeenet_driver_s *)dev->d_private;
+  FAR struct xbeenet_driver_s *priv =
+    (FAR struct xbeenet_driver_s *)dev->d_private;
   int ret = -EINVAL;
 
   ret = nxsem_wait(&priv->xd_exclsem);
@@ -1016,12 +1038,13 @@ static int xbeenet_ioctl(FAR struct net_driver_s *dev, int cmd,
           switch (cmd)
             {
               /* Command:     MAC802154IOC_NOTIFY_REGISTER
-               * Description: Register to receive a signal whenever there is a
-               *              event primitive sent from the MAC layer.
+               * Description: Register to receive a signal whenever there is
+               *              an event primitive sent from the MAC layer.
                * Argument:    A read-only pointer to an instance of struct
                *              xbeenet_notify_s
-               * Return:      Zero (OK) on success.  Minus one will be returned on
-               *              failure with the errno value set appropriately.
+               * Return:      Zero (OK) on success.  Minus one will be
+               *              returned on failure with the errno value set
+               *              appropriately.
                */
 
               case MAC802154IOC_NOTIFY_REGISTER:
@@ -1046,8 +1069,8 @@ static int xbeenet_ioctl(FAR struct net_driver_s *dev, int cmd,
                       primitive = (FAR struct ieee802154_primitive_s *)
                                       sq_remfirst(&priv->primitive_queue);
 
-                      /* If there was an event to pop off, copy it into the user
-                       * data and free it from the MAC layer's memory.
+                      /* If there was an event to pop off, copy it into the
+                       * user data and free it from the MAC layer's memory.
                        */
 
                       if (primitive != NULL)
@@ -1082,8 +1105,8 @@ static int xbeenet_ioctl(FAR struct net_driver_s *dev, int cmd,
                           return ret;
                         }
 
-                      /* Get exclusive access again, then loop back around and try and
-                       * pop an event off the queue
+                      /* Get exclusive access again, then loop back around
+                       * and try and pop an event off the queue
                        */
 
                       ret = nxsem_wait(&priv->xd_exclsem);
@@ -1352,12 +1375,12 @@ int xbee_netdev_register(XBEEHANDLE xbee)
  #ifdef CONFIG_NETDEV_IOCTL
   dev->d_ioctl        = xbeenet_ioctl;      /* Handle network IOCTL commands */
 #endif
-  dev->d_private      = (FAR void *)priv;  /* Used to recover private state from dev */
+  dev->d_private      = (FAR void *)priv;   /* Used to recover private state from dev */
 
   /* Create a watchdog for timing polling for and timing of transmissions */
 
   priv->xd_mac        = xbee;               /* Save the MAC interface instance */
-  priv->xd_txpoll     = wd_create();       /* Create periodic poll timer */
+  priv->xd_txpoll     = wd_create();        /* Create periodic poll timer */
 
   /* Setup a locking semaphore for exclusive device driver access */
 
@@ -1417,9 +1440,9 @@ int xbee_netdev_register(XBEEHANDLE xbee)
   xbeenet_ifdown(dev);
 
 #ifdef CONFIG_NET_6LOWPAN
-  /* Make sure the our single packet buffer is attached. We must do this before
-   * registering the device since, once the device is registered, a packet may
-   * be attempted to be forwarded and require the buffer.
+  /* Make sure the our single packet buffer is attached. We must do this
+   * before registering the device since, once the device is registered, a
+   * packet may be attempted to be forwarded and require the buffer.
    */
 
   priv->xd_dev.r_dev.d_buf = g_iobuffer.rb_buf;
diff --git a/fs/hostfs/hostfs_rpmsg.c b/fs/hostfs/hostfs_rpmsg.c
index b23970f..dea16a2 100644
--- a/fs/hostfs/hostfs_rpmsg.c
+++ b/fs/hostfs/hostfs_rpmsg.c
@@ -280,8 +280,9 @@ static void hostfs_rpmsg_device_destroy(FAR struct rpmsg_device *rdev,
     }
 }
 
-static int hostfs_rpmsg_ept_cb(FAR struct rpmsg_endpoint *ept, FAR void *data,
-                               size_t len, uint32_t src, FAR void *priv)
+static int hostfs_rpmsg_ept_cb(FAR struct rpmsg_endpoint *ept,
+                               FAR void *data, size_t len, uint32_t src,
+                               FAR void *priv)
 {
   FAR struct hostfs_rpmsg_header_s *header = data;
   uint32_t command = header->command;
@@ -441,7 +442,8 @@ ssize_t host_write(int fd, FAR const void *buf, size_t count)
       memcpy(msg->buf, buf + written, space);
 
       ret = hostfs_rpmsg_send_recv(HOSTFS_RPMSG_WRITE, false,
-                (struct hostfs_rpmsg_header_s *)msg, sizeof(*msg) + space, NULL);
+                                   (FAR struct hostfs_rpmsg_header_s *)msg,
+                                   sizeof(*msg) + space, NULL);
       if (ret <= 0)
         {
           break;
diff --git a/graphics/nxterm/nxterm_register.c b/graphics/nxterm/nxterm_register.c
index 49b749e..644b6ef 100644
--- a/graphics/nxterm/nxterm_register.c
+++ b/graphics/nxterm/nxterm_register.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * nuttx/graphics/nxterm/nxterm_register.c
  *
- *   Copyright (C) 2012, 2016-2017 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.
  *
  ****************************************************************************/
 
@@ -74,7 +59,8 @@ FAR struct nxterm_state_s *
 
   /* Allocate the driver structure */
 
-  priv = (FAR struct nxterm_state_s *)kmm_zalloc(sizeof(struct nxterm_state_s));
+  priv = (FAR struct nxterm_state_s *)
+    kmm_zalloc(sizeof(struct nxterm_state_s));
   if (!priv)
     {
       gerr("ERROR: Failed to allocate the NX driver structure\n");
diff --git a/include/nuttx/mutex.h b/include/nuttx/mutex.h
index f23bf0c..78032d8 100644
--- a/include/nuttx/mutex.h
+++ b/include/nuttx/mutex.h
@@ -123,9 +123,10 @@ static inline int nxmutex_destroy(FAR mutex_t *mutex)
  * Name: nxmutex_lock
  *
  * Description:
- *   This function attempts to lock the mutex referenced by 'mutex'.  The mutex
- *   is implemented with a semaphore, so if the semaphore value is (<=) zero,
- *   then the calling task will not return until it successfully acquires the lock.
+ *   This function attempts to lock the mutex referenced by 'mutex'.  The
+ *   mutex is implemented with a semaphore, so if the semaphore value is
+ *   (<=) zero, then the calling task will not return until it successfully
+ *   acquires the lock.
  *
  * Parameters:
  *   mutex - mutex descriptor.
diff --git a/net/arp/arp_send.c b/net/arp/arp_send.c
index 5f4d27a..698ec55 100644
--- a/net/arp/arp_send.c
+++ b/net/arp/arp_send.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/arp/arp_send.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.
  *
  ****************************************************************************/
 
@@ -205,8 +190,8 @@ int arp_send(in_addr_t ipaddr)
 #ifdef CONFIG_NET_IGMP
   /* Check if the destination address is a multicast address
    *
-   * - IPv4: multicast addresses lie in the class D group -- The address range
-   *   224.0.0.0 to 239.255.255.255 (224.0.0.0/4)
+   * - IPv4: multicast addresses lie in the class D group -- The address
+   *   range 224.0.0.0 to 239.255.255.255 (224.0.0.0/4)
    *
    * - IPv6 multicast addresses are have the high-order octet of the
    *   addresses=0xff (ff00::/8.)
diff --git a/net/bluetooth/bluetooth_recvfrom.c b/net/bluetooth/bluetooth_recvfrom.c
index 702c140..0f35d24 100644
--- a/net/bluetooth/bluetooth_recvfrom.c
+++ b/net/bluetooth/bluetooth_recvfrom.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/socket/bluetooth_recvfrom.c
  *
- *   Copyright (C) 2018 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.
  *
  ****************************************************************************/
 
@@ -129,8 +114,9 @@ static int bluetooth_count_frames(FAR struct bluetooth_conn_s *conn)
  *
  ****************************************************************************/
 
-static ssize_t bluetooth_recvfrom_rxqueue(FAR struct radio_driver_s *radio,
-                                           FAR struct bluetooth_recvfrom_s *pstate)
+static ssize_t
+  bluetooth_recvfrom_rxqueue(FAR struct radio_driver_s *radio,
+                             FAR struct bluetooth_recvfrom_s *pstate)
 {
   FAR struct bluetooth_container_s *container;
   FAR struct sockaddr_bt_s *iaddr;
@@ -290,9 +276,9 @@ static uint16_t bluetooth_recvfrom_eventhandler(FAR struct net_driver_s *dev,
  *
  * Description:
  *   Implements the socket recvfrom interface for the case of the AF_INET
- *   and AF_INET6 address families.  bluetooth_recvfrom() receives messages from
- *   a socket, and may be used to receive data on a socket whether or not it
- *   is connection-oriented.
+ *   and AF_INET6 address families.  bluetooth_recvfrom() receives messages
+ *   from a socket, and may be used to receive data on a socket whether or
+ *   not it is connection-oriented.
  *
  *   If 'from' is not NULL, and the underlying protocol provides the source
  *   address, this source address is filled in.  The argument 'fromlen' is
@@ -323,7 +309,8 @@ ssize_t bluetooth_recvfrom(FAR struct socket *psock, FAR void *buf,
                             size_t len, int flags, FAR struct sockaddr *from,
                             FAR socklen_t *fromlen)
 {
-  FAR struct bluetooth_conn_s *conn = (FAR struct bluetooth_conn_s *)psock->s_conn;
+  FAR struct bluetooth_conn_s *conn =
+    (FAR struct bluetooth_conn_s *)psock->s_conn;
   FAR struct radio_driver_s *radio;
   struct bluetooth_recvfrom_s state;
   ssize_t ret;
diff --git a/net/bluetooth/bluetooth_sendto.c b/net/bluetooth/bluetooth_sendto.c
index 24578cd..3dbfcc6 100644
--- a/net/bluetooth/bluetooth_sendto.c
+++ b/net/bluetooth/bluetooth_sendto.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/bluetooth/bluetooth_sendto.c
  *
- *   Copyright (C) 2018 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.
  *
  ****************************************************************************/
 
@@ -246,8 +231,9 @@ errout:
  ****************************************************************************/
 
 ssize_t psock_bluetooth_sendto(FAR struct socket *psock, FAR const void *buf,
-                                size_t len, int flags,
-                                FAR const struct sockaddr *to, socklen_t tolen)
+                               size_t len, int flags,
+                               FAR const struct sockaddr *to,
+                               socklen_t tolen)
 {
   FAR struct sockaddr_bt_s *destaddr;
   FAR struct radio_driver_s *radio;
@@ -349,8 +335,9 @@ ssize_t psock_bluetooth_sendto(FAR struct socket *psock, FAR const void *buf,
       return state.is_sent;
     }
 
-  /* If net_lockedwait failed, then we were probably reawakened by a signal. In
-   * this case, net_lockedwait will have returned negated errno appropriately.
+  /* If net_lockedwait failed, then we were probably reawakened by a signal.
+   * In this case, net_lockedwait will have returned negated errno
+   * appropriately.
    */
 
   if (ret < 0)
diff --git a/net/icmp/icmp_recvfrom.c b/net/icmp/icmp_recvfrom.c
index 4f23985..f8cb5ca 100644
--- a/net/icmp/icmp_recvfrom.c
+++ b/net/icmp/icmp_recvfrom.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/icmp/icmp_recvfrom.c
  *
- *   Copyright (C) 2017, 2019 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.
  *
  ****************************************************************************/
 
@@ -69,13 +54,15 @@
 struct icmp_recvfrom_s
 {
   FAR struct devif_callback_s *recv_cb; /* Reference to callback instance */
-  FAR struct socket *recv_sock; /* IPPROTO_ICMP socket structure */
-  sem_t recv_sem;               /* Use to manage the wait for the response */
-  in_addr_t recv_from;          /* The peer we received the request from */
-  FAR uint8_t *recv_buf;        /* Location to return the response */
-  uint16_t recv_buflen;         /* Size of the response */
-  int16_t recv_result;          /* >=0: receive size on success;
-                                 * <0: negated errno on fail */
+  FAR struct socket *recv_sock;         /* IPPROTO_ICMP socket structure */
+  sem_t recv_sem;                       /* Use to manage the wait for the
+                                         * response */
+  in_addr_t recv_from;                  /* The peer we received the request
+                                         * from */
+  FAR uint8_t *recv_buf;                /* Location to return the response */
+  uint16_t recv_buflen;                 /* Size of the response */
+  int16_t recv_result;                  /* >=0: receive size on success;
+                                         * <0: negated errno on fail */
 };
 
 /****************************************************************************
@@ -248,7 +235,9 @@ static inline ssize_t icmp_readahead(FAR struct icmp_conn_s *conn,
   ssize_t ret = -ENODATA;
   int recvlen;
 
-  /* Check there is any ICMP replies already buffered in a read-ahead buffer. */
+  /* Check there is any ICMP replies already buffered in a read-ahead
+   * buffer.
+   */
 
   if ((iob = iob_peek_queue(&conn->readahead)) != NULL)
     {
diff --git a/net/icmp/icmp_sendto.c b/net/icmp/icmp_sendto.c
index cb172be..8ae0587 100644
--- a/net/icmp/icmp_sendto.c
+++ b/net/icmp/icmp_sendto.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/icmp/icmp_sendto.c
  *
- *   Copyright (C) 2017, 2019-2020 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.
  *
  ****************************************************************************/
 
@@ -86,11 +71,14 @@
 struct icmp_sendto_s
 {
   FAR struct devif_callback_s *snd_cb; /* Reference to callback instance */
-  sem_t snd_sem;               /* Use to manage the wait for send complete */
-  in_addr_t snd_toaddr;        /* The peer to send the request to */
-  FAR const uint8_t *snd_buf;  /* ICMP header + data payload */
-  uint16_t snd_buflen;         /* Size of the ICMP header + data payload */
-  int16_t snd_result;          /* 0: success; <0:negated errno on fail */
+  sem_t snd_sem;                       /* Use to manage the wait for send
+                                        * complete */
+  in_addr_t snd_toaddr;                /* The peer to send the request to */
+  FAR const uint8_t *snd_buf;          /* ICMP header + data payload */
+  uint16_t snd_buflen;                 /* Size of the ICMP header + data
+                                        * payload */
+  int16_t snd_result;                  /* 0: success; <0:negated errno on
+                                        * fail */
 };
 
 /****************************************************************************
@@ -295,8 +283,9 @@ end_wait:
  *
  ****************************************************************************/
 
-ssize_t icmp_sendto(FAR struct socket *psock, FAR const void *buf, size_t len,
-                    int flags, FAR const struct sockaddr *to, socklen_t tolen)
+ssize_t icmp_sendto(FAR struct socket *psock, FAR const void *buf,
+                    size_t len, int flags, FAR const struct sockaddr *to,
+                    socklen_t tolen)
 {
   FAR const struct sockaddr_in *inaddr;
   FAR struct net_driver_s *dev;
@@ -367,10 +356,12 @@ ssize_t icmp_sendto(FAR struct socket *psock, FAR const void *buf, size_t len,
   nxsem_init(&state.snd_sem, 0, 0);
   nxsem_set_protocol(&state.snd_sem, SEM_PRIO_NONE);
 
-  state.snd_result = -ENOMEM;          /* Assume allocation failure */
-  state.snd_toaddr = inaddr->sin_addr.s_addr; /* Address of the peer to send the request */
-  state.snd_buf    = buf;              /* ICMP header + data payload */
-  state.snd_buflen = len;              /* Size of the ICMP header + data payload */
+  state.snd_result = -ENOMEM;                 /* Assume allocation failure */
+  state.snd_toaddr = inaddr->sin_addr.s_addr; /* Address of the peer to send
+                                               * the request */
+  state.snd_buf    = buf;                     /* ICMP header + data payload */
+  state.snd_buflen = len;                     /* Size of the ICMP header +
+                                               * data payload */
 
   net_lock();
 
@@ -406,16 +397,17 @@ ssize_t icmp_sendto(FAR struct socket *psock, FAR const void *buf, size_t len,
         {
           if (ret == -ETIMEDOUT)
             {
-              /* Check if this device is on the same network as the destination
-               * device.
+              /* Check if this device is on the same network as the
+               * destination device.
                */
 
               if (!net_ipv4addr_maskcmp(state.snd_toaddr, dev->d_ipaddr,
                                         dev->d_netmask))
                 {
-                  /* Destination address was not on the local network served by
-                   * this device.  If a timeout occurs, then the most likely
-                   * reason is that the destination address is not reachable.
+                  /* Destination address was not on the local network served
+                   * by this device.  If a timeout occurs, then the most
+                   * likely reason is that the destination address is not
+                   * reachable.
                    */
 
                   ret = -ENETUNREACH;
diff --git a/net/icmpv6/icmpv6_autoconfig.c b/net/icmpv6/icmpv6_autoconfig.c
index e2fced5..02aa42a 100644
--- a/net/icmpv6/icmpv6_autoconfig.c
+++ b/net/icmpv6/icmpv6_autoconfig.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/icmpv6/icmpv6_autoconfig.c
  *
- *   Copyright (C) 2015-2016, 2018-2020 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.
  *
  ****************************************************************************/
 
@@ -123,9 +108,9 @@ static uint16_t icmpv6_router_eventhandler(FAR struct net_driver_s *dev,
         }
 
       /* Check if the outgoing packet is available. It may have been claimed
-       * by a send event handler serving a different thread -OR- if the output
-       * buffer currently contains unprocessed incoming data. In these cases
-       * we will just have to wait for the next polling cycle.
+       * by a send event handler serving a different thread -OR- if the
+       * output buffer currently contains unprocessed incoming data. In
+       * these cases we will just have to wait for the next polling cycle.
        */
 
       else if (dev->d_sndlen > 0 || (flags & ICMPv6_NEWDATA) != 0)
@@ -326,20 +311,22 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
   icmpv6_linkipaddr(dev, lladdr);
 
   ninfo("lladdr=%04x:%04x:%04x:%04x:%04x:%04x:%04x:%04x\n",
-        ntohs(lladdr[0]), ntohs(lladdr[1]), ntohs(lladdr[2]), ntohs(lladdr[3]),
-        ntohs(lladdr[4]), ntohs(lladdr[5]), ntohs(lladdr[6]), ntohs(lladdr[7]));
+        ntohs(lladdr[0]), ntohs(lladdr[1]),
+        ntohs(lladdr[2]), ntohs(lladdr[3]),
+        ntohs(lladdr[4]), ntohs(lladdr[5]),
+        ntohs(lladdr[6]), ntohs(lladdr[7]));
 
 #ifdef CONFIG_NET_ICMPv6_NEIGHBOR
   /* 2. Link-Local Address Uniqueness Test:  The node tests to ensure that
    *    the address it generated isn't for some reason already in use on the
-   *    local network. (This is very unlikely to be an issue if the link-local
-   *    address came from a MAC address but more likely if it was based on a
-   *    generated token.) It sends a Neighbor Solicitation message using the
-   *    Neighbor Discovery (ND) protocol. It then listens for a Neighbor
-   *    Advertisement in response that indicates that another device is
-   *    already using its link-local address; if so, either a new address
-   *    must be generated, or auto-configuration fails and another method
-   *    must be employed.
+   *    local network. (This is very unlikely to be an issue if the link-
+   *    local address came from a MAC address but more likely if it was
+   *    based on a generated token.) It sends a Neighbor Solicitation
+   *    message using the Neighbor Discovery (ND) protocol. It then listens
+   *    for a Neighbor Advertisement in response that indicates that another
+   *    device is already using its link-local address; if so, either a new
+   *    address  must be generated, or auto-configuration fails and another
+   *    method must be employed.
    */
 
   ret = icmpv6_neighbor(lladdr);
@@ -409,7 +396,8 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
     {
       int senderr;
 
-      nerr("ERROR: Failed to get the router advertisement: %d (retries=%d)\n",
+      nerr("ERROR: Failed to get the router advertisement: "
+           "%d (retries=%d)\n",
            ret, retries);
 
       /* Claim the link local address as ours by sending the ICMPv6 Neighbor
@@ -431,11 +419,11 @@ int icmpv6_autoconfig(FAR struct net_driver_s *dev)
       net_ipv6addr_copy(dev->d_ipv6netmask, g_ipv6_llnetmask);
     }
 
-  /* 5. Router Direction: The router provides direction to the node on how to
-   *    proceed with the auto-configuration. It may tell the node that on this
-   *    network "stateful" auto-configuration is in use, and tell it the
-   *    address of a DHCP server to use. Alternately, it will tell the host
-   *    how to determine its global Internet address.
+  /* 5. Router Direction: The router provides direction to the node on how
+   *    to proceed with the auto-configuration. It may tell the node that on
+   *    this network "stateful" auto-configuration is in use, and tell it
+   *    the address of a DHCP server to use. Alternately, it will tell the
+   *    host how to determine its global Internet address.
    *
    * 6. Global Address Configuration: Assuming that stateless auto-
    *    configuration is in use on the network, the host will configure
diff --git a/net/icmpv6/icmpv6_neighbor.c b/net/icmpv6/icmpv6_neighbor.c
index 6f67958..089ee34 100644
--- a/net/icmpv6/icmpv6_neighbor.c
+++ b/net/icmpv6/icmpv6_neighbor.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/icmpv6/icmpv6_neighbor.c
  *
- *   Copyright (C) 2015-2016, 2019 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.
  *
  ****************************************************************************/
 
@@ -108,9 +93,9 @@ static uint16_t icmpv6_neighbor_eventhandler(FAR struct net_driver_s *dev,
         }
 
       /* Check if the outgoing packet is available. It may have been claimed
-       * by a send event handler serving a different thread -OR- if the output
-       * buffer currently contains unprocessed incoming data. In these cases
-       * we will just have to wait for the next polling cycle.
+       * by a send event handler serving a different thread -OR- if the
+       * output buffer currently contains unprocessed incoming data.  In
+       * these cases we will just have to wait for the next polling cycle.
        */
 
       if (dev->d_sndlen > 0 || (flags & ICMPv6_NEWDATA) != 0)
@@ -174,7 +159,8 @@ static uint16_t icmpv6_neighbor_eventhandler(FAR struct net_driver_s *dev,
  *
  * Returned Value:
  *   Zero (OK) is returned on success and the IP address mapping can now be
- *   found in the Neighbor Table.  On error a negated errno value is returned:
+ *   found in the Neighbor Table.  On error a negated errno value is
+ *   returned:
  *
  *     -ETIMEDOUT:    The number or retry counts has been exceed.
  *     -EHOSTUNREACH: Could not find a route to the host
@@ -290,8 +276,8 @@ int icmpv6_neighbor(const net_ipv6addr_t ipaddr)
       /* Check if the address mapping is present in the Neighbor Table.  This
        * is only really meaningful on the first time through the loop.
        *
-       * NOTE: If the Neighbor Table is large than this could be a performance
-       * issue.
+       * NOTE: If the Neighbor Table is large than this could be a
+       * performance issue.
        */
 
       if (neighbor_lookup(lookup, NULL) >= 0)
@@ -329,7 +315,9 @@ int icmpv6_neighbor(const net_ipv6addr_t ipaddr)
         }
       while (!state.snd_sent);
 
-      /* Now wait for response to the Neighbor Advertisement to be received. */
+      /* Now wait for response to the Neighbor Advertisement to be
+       * received.
+       */
 
       ret = icmpv6_wait(&notify, CONFIG_ICMPv6_NEIGHBOR_DELAYMSEC);
 
diff --git a/net/icmpv6/icmpv6_recvfrom.c b/net/icmpv6/icmpv6_recvfrom.c
index a19aac1..1ed07094 100644
--- a/net/icmpv6/icmpv6_recvfrom.c
+++ b/net/icmpv6/icmpv6_recvfrom.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/icmpv6/icmpv6_recvfrom.c
  *
- *   Copyright (C) 2017, 2019 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.
  *
  ****************************************************************************/
 
@@ -72,13 +57,15 @@
 struct icmpv6_recvfrom_s
 {
   FAR struct devif_callback_s *recv_cb; /* Reference to callback instance */
-  FAR struct socket *recv_sock; /* IPPROTO_ICMP6 socket structure */
-  sem_t recv_sem;               /* Use to manage the wait for the response */
-  struct in6_addr recv_from;    /* The peer we received the request from */
-  FAR uint8_t *recv_buf;        /* Location to return the response */
-  uint16_t recv_buflen;         /* Size of the response */
-  int16_t recv_result;          /* >=0: receive size on success;
-                                 * <0: negated errno on fail */
+  FAR struct socket *recv_sock;         /* IPPROTO_ICMP6 socket structure */
+  sem_t recv_sem;                       /* Use to manage the wait for the
+                                         * response */
+  struct in6_addr recv_from;            /* The peer we received the request
+                                         * from */
+  FAR uint8_t *recv_buf;                /* Location to return the response */
+  uint16_t recv_buflen;                 /* Size of the response */
+  int16_t recv_result;                  /* >=0: receive size on success;
+                                         * <0: negated errno on fail */
 };
 
 /****************************************************************************
@@ -255,7 +242,9 @@ static inline ssize_t icmpv6_readahead(FAR struct icmpv6_conn_s *conn,
   ssize_t ret = -ENODATA;
   int recvlen;
 
-  /* Check there is any ICMPv6 replies already buffered in a read-ahead buffer. */
+  /* Check there is any ICMPv6 replies already buffered in a read-ahead
+   * buffer.
+   */
 
   if ((iob = iob_peek_queue(&conn->readahead)) != NULL)
     {
diff --git a/net/icmpv6/icmpv6_sendto.c b/net/icmpv6/icmpv6_sendto.c
index 833821f..3ee6881 100644
--- a/net/icmpv6/icmpv6_sendto.c
+++ b/net/icmpv6/icmpv6_sendto.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/icmpv6/icmpv6_sendto.c
  *
- *   Copyright (C) 2017, 2019-2020 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.
  *
  ****************************************************************************/
 
@@ -85,11 +70,14 @@
 struct icmpv6_sendto_s
 {
   FAR struct devif_callback_s *snd_cb; /* Reference to callback instance */
-  sem_t snd_sem;               /* Use to manage the wait for send complete */
-  struct in6_addr snd_toaddr;  /* The peer to send the request to */
-  FAR const uint8_t *snd_buf;  /* ICMPv6 header + data payload */
-  uint16_t snd_buflen;         /* Size of the ICMPv6 header + data payload */
-  int16_t snd_result;          /* 0: success; <0:negated errno on fail */
+  sem_t snd_sem;                       /* Use to manage the wait for send
+                                        * complete */
+  struct in6_addr snd_toaddr;          /* The peer to send the request to */
+  FAR const uint8_t *snd_buf;          /* ICMPv6 header + data payload */
+  uint16_t snd_buflen;                 /* Size of the ICMPv6 header + data
+                                        * payload */
+  int16_t snd_result;                  /* 0: success; <0:negated errno on
+                                        * fail */
 };
 
 /****************************************************************************
@@ -267,8 +255,8 @@ end_wait:
  *   Implements the sendto() operation for the case of the IPPROTO_ICMP6
  *   socket.  The 'buf' parameter points to a block of memory that includes
  *   an ICMPv6 request header, followed by any payload that accompanies the
- *   request.  The 'len' parameter includes both the size of the ICMPv6 header
- *   and the following payload.
+ *   request.  The 'len' parameter includes both the size of the ICMPv6
+ *   header and the following payload.
  *
  * Input Parameters:
  *   psock    A pointer to a NuttX-specific, internal socket structure
@@ -285,8 +273,9 @@ end_wait:
  *
  ****************************************************************************/
 
-ssize_t icmpv6_sendto(FAR struct socket *psock, FAR const void *buf, size_t len,
-                    int flags, FAR const struct sockaddr *to, socklen_t tolen)
+ssize_t icmpv6_sendto(FAR struct socket *psock, FAR const void *buf,
+                      size_t len, int flags, FAR const struct sockaddr *to,
+                      socklen_t tolen)
 {
   FAR const struct sockaddr_in6 *inaddr;
   FAR struct net_driver_s *dev;
@@ -399,16 +388,17 @@ ssize_t icmpv6_sendto(FAR struct socket *psock, FAR const void *buf, size_t len,
         {
           if (ret == -ETIMEDOUT)
             {
-              /* Check if this device is on the same network as the destination
-               * device.
+              /* Check if this device is on the same network as the
+               * destination device.
                */
 
               if (!net_ipv6addr_maskcmp(state.snd_toaddr.s6_addr16,
                                         dev->d_ipv6addr, dev->d_ipv6netmask))
                 {
-                  /* Destination address was not on the local network served by
-                   * this device.  If a timeout occurs, then the most likely
-                   * reason is that the destination address is not reachable.
+                  /* Destination address was not on the local network served
+                   * by this device.  If a timeout occurs, then the most
+                   * likely reason is that the destination address is not
+                   * reachable.
                    */
 
                   ret = -ENETUNREACH;
diff --git a/net/ieee802154/ieee802154_recvfrom.c b/net/ieee802154/ieee802154_recvfrom.c
index 691c0f6..e58df4e 100644
--- a/net/ieee802154/ieee802154_recvfrom.c
+++ b/net/ieee802154/ieee802154_recvfrom.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/socket/ieee802154_recvfrom.c
  *
- *   Copyright (C) 2017 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.
  *
  ****************************************************************************/
 
@@ -127,8 +112,9 @@ static int ieee802154_count_frames(FAR struct ieee802154_conn_s *conn)
  *
  ****************************************************************************/
 
-static ssize_t ieee802154_recvfrom_rxqueue(FAR struct radio_driver_s *radio,
-                                           FAR struct ieee802154_recvfrom_s *pstate)
+static ssize_t
+  ieee802154_recvfrom_rxqueue(FAR struct radio_driver_s *radio,
+                              FAR struct ieee802154_recvfrom_s *pstate)
 {
   FAR struct ieee802154_container_s *container;
   FAR struct sockaddr_ieee802154_s *iaddr;
@@ -187,8 +173,10 @@ static ssize_t ieee802154_recvfrom_rxqueue(FAR struct radio_driver_s *radio,
 
       if (pstate->ir_from != NULL)
         {
-          iaddr            = (FAR struct sockaddr_ieee802154_s *)pstate->ir_from;
+          iaddr            = (FAR struct sockaddr_ieee802154_s *)
+                             pstate->ir_from;
           iaddr->sa_family = AF_IEEE802154;
+
           memcpy(&iaddr->sa_addr, &container->ic_src,
                  sizeof(struct ieee802154_saddr_s));
         }
@@ -216,10 +204,10 @@ static ssize_t ieee802154_recvfrom_rxqueue(FAR struct radio_driver_s *radio,
  *
  ****************************************************************************/
 
-static uint16_t ieee802154_recvfrom_eventhandler(FAR struct net_driver_s *dev,
-                                                 FAR void *pvconn,
-                                                 FAR void *pvpriv,
-                                                 uint16_t flags)
+static uint16_t
+  ieee802154_recvfrom_eventhandler(FAR struct net_driver_s *dev,
+                                   FAR void *pvconn, FAR void *pvpriv,
+                                   uint16_t flags)
 {
   FAR struct ieee802154_recvfrom_s *pstate;
   FAR struct radio_driver_s *radio;
@@ -288,9 +276,9 @@ static uint16_t ieee802154_recvfrom_eventhandler(FAR struct net_driver_s *dev,
  *
  * Description:
  *   Implements the socket recvfrom interface for the case of the AF_INET
- *   and AF_INET6 address families.  ieee802154_recvfrom() receives messages from
- *   a socket, and may be used to receive data on a socket whether or not it
- *   is connection-oriented.
+ *   and AF_INET6 address families.  ieee802154_recvfrom() receives messages
+ *   from a socket, and may be used to receive data on a socket whether or
+ *   not it is connection-oriented.
  *
  *   If 'from' is not NULL, and the underlying protocol provides the source
  *   address, this source address is filled in.  The argument 'fromlen' is
@@ -321,7 +309,8 @@ ssize_t ieee802154_recvfrom(FAR struct socket *psock, FAR void *buf,
                             size_t len, int flags, FAR struct sockaddr *from,
                             FAR socklen_t *fromlen)
 {
-  FAR struct ieee802154_conn_s *conn = (FAR struct ieee802154_conn_s *)psock->s_conn;
+  FAR struct ieee802154_conn_s *conn =
+    (FAR struct ieee802154_conn_s *)psock->s_conn;
   FAR struct radio_driver_s *radio;
   struct ieee802154_recvfrom_s state;
   ssize_t ret;
diff --git a/net/ieee802154/ieee802154_sendto.c b/net/ieee802154/ieee802154_sendto.c
index 41d7421..05dae32 100644
--- a/net/ieee802154/ieee802154_sendto.c
+++ b/net/ieee802154/ieee802154_sendto.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/ieee802154/ieee802154_sendto.c
  *
- *   Copyright (C) 2017-2018 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.
  *
  ****************************************************************************/
 
@@ -433,9 +418,10 @@ errout:
  *
  ****************************************************************************/
 
-ssize_t psock_ieee802154_sendto(FAR struct socket *psock, FAR const void *buf,
-                                size_t len, int flags,
-                                FAR const struct sockaddr *to, socklen_t tolen)
+ssize_t psock_ieee802154_sendto(FAR struct socket *psock,
+                                FAR const void *buf, size_t len, int flags,
+                                FAR const struct sockaddr *to,
+                                socklen_t tolen)
 {
   FAR struct sockaddr_ieee802154_s *destaddr;
   FAR struct radio_driver_s *radio;
@@ -538,8 +524,9 @@ ssize_t psock_ieee802154_sendto(FAR struct socket *psock, FAR const void *buf,
       return state.is_sent;
     }
 
-  /* If net_lockedwait failed, then we were probably reawakened by a signal. In
-   * this case, net_lockedwait will have returned negated errno appropriately.
+  /* If net_lockedwait failed, then we were probably reawakened by a signal.
+   * In this case, net_lockedwait will have returned negated errno
+   * appropriately.
    */
 
   if (ret < 0)
diff --git a/net/local/local_connect.c b/net/local/local_connect.c
index d4a83e3..ffafa2b 100644
--- a/net/local/local_connect.c
+++ b/net/local/local_connect.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/local/local_connect.c
  *
- *   Copyright (C) 2015-2017 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.
  *
  ****************************************************************************/
 
@@ -305,7 +290,8 @@ int psock_local_connect(FAR struct socket *psock,
                 /* Bind the address and protocol */
 
                 client->lc_proto = conn->lc_proto;
-                strncpy(client->lc_path, unaddr->sun_path, UNIX_PATH_MAX - 1);
+                strncpy(client->lc_path, unaddr->sun_path,
+                        UNIX_PATH_MAX - 1);
                 client->lc_path[UNIX_PATH_MAX - 1] = '\0';
                 client->lc_instance_id = local_generate_instance_id();
 
@@ -317,8 +303,9 @@ int psock_local_connect(FAR struct socket *psock,
 
                 if (conn->lc_proto == SOCK_STREAM)
                   {
-                    ret = local_stream_connect(client, conn,
-                                               _SS_ISNONBLOCK(psock->s_flags));
+                    ret =
+                      local_stream_connect(client, conn,
+                                           _SS_ISNONBLOCK(psock->s_flags));
                   }
                 else
                   {
diff --git a/net/tcp/tcp_connect.c b/net/tcp/tcp_connect.c
index 08fe885..809a48e 100644
--- a/net/tcp/tcp_connect.c
+++ b/net/tcp/tcp_connect.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/tcp/tcp_connect.c
  *
- *   Copyright (C) 2007-2012, 2015-2017 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.
  *
  ****************************************************************************/
 
@@ -195,8 +180,8 @@ static uint16_t psock_connect_eventhandler(FAR struct net_driver_s *dev,
        *     ENETUNREACH
        *       Network is unreachable.
        *     ETIMEDOUT
-       *       Timeout while attempting connection. The server may be too busy
-       *       to accept new connections.
+       *       Timeout while attempting connection. The server may be too
+       *       busy to accept new connections.
        */
 
       /* TCP_CLOSE: The remote host has closed the connection
@@ -292,7 +277,8 @@ static uint16_t psock_connect_eventhandler(FAR struct net_driver_s *dev,
  *   Perform a TCP connection
  *
  * Input Parameters:
- *   psock - A reference to the socket structure of the socket to be connected
+ *   psock - A reference to the socket structure of the socket to be
+ *           connected
  *   addr  - The address of the remote server to connect to
  *
  * Returned Value:
diff --git a/net/tcp/tcp_recvfrom.c b/net/tcp/tcp_recvfrom.c
index a354c3f..6d040ae 100644
--- a/net/tcp/tcp_recvfrom.c
+++ b/net/tcp/tcp_recvfrom.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * net/tcp/tcp_recvfrom.c
  *
- *   Copyright (C) 2020 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.
  *
  ****************************************************************************/
 
@@ -249,7 +234,8 @@ static inline void tcp_newdata(FAR struct net_driver_s *dev,
 
 static inline void tcp_readahead(struct tcp_recvfrom_s *pstate)
 {
-  FAR struct tcp_conn_s *conn = (FAR struct tcp_conn_s *)pstate->ir_sock->s_conn;
+  FAR struct tcp_conn_s *conn =
+    (FAR struct tcp_conn_s *)pstate->ir_sock->s_conn;
   FAR struct iob_s *iob;
   int recvlen;
 
@@ -607,8 +593,9 @@ static ssize_t tcp_recvfrom_result(int result, struct tcp_recvfrom_s *pstate)
       return pstate->ir_result;
     }
 
-  /* If net_timedwait failed, then we were probably reawakened by a signal. In
-   * this case, net_timedwait will have returned negated errno appropriately.
+  /* If net_timedwait failed, then we were probably reawakened by a signal.
+   * In this case, net_timedwait will have returned negated errno
+   * appropriately.
    */
 
   if (result < 0)
@@ -683,15 +670,15 @@ ssize_t psock_tcp_recvfrom(FAR struct socket *psock, FAR void *buf,
        * will wait to return end disconnection indications the next time that
        * recvfrom() is called.
        *
-       * If no data was received (i.e.,  ret == 0  -- it will not be negative)
-       * and the connection was gracefully closed by the remote peer, then return
-       * success.  If ir_recvlen is zero, the caller of recvfrom() will get an
-       * end-of-file indication.
+       * If no data was received (i.e.,  ret == 0  -- it will not be
+       * negative) and the connection was gracefully closed by the remote
+       * peer, then return success.  If ir_recvlen is zero, the caller of
+       * recvfrom() will get an end-of-file indication.
        */
 
       if (ret <= 0 && !_SS_ISCLOSED(psock->s_flags))
         {
-          /* Nothing was previously received from the readahead buffers.
+          /* Nothing was previously received from the read-ahead buffers.
            * The SOCK_STREAM must be (re-)connected in order to receive any
            * additional data.
            */
@@ -701,9 +688,9 @@ ssize_t psock_tcp_recvfrom(FAR struct socket *psock, FAR void *buf,
     }
 
   /* In general, this implementation will not support non-blocking socket
-   * operations... except in a few cases:  Here for TCP receive with read-ahead
-   * enabled.  If this socket is configured as non-blocking then return EAGAIN
-   * if no data was obtained from the read-ahead buffers.
+   * operations... except in a few cases:  Here for TCP receive with read-
+   * ahead enabled.  If this socket is configured as non-blocking then
+   * return EAGAIN if no data was obtained from the read-ahead buffers.
    */
 
   else if (_SS_ISNONBLOCK(psock->s_flags) || (flags & MSG_DONTWAIT) != 0)
@@ -720,15 +707,15 @@ ssize_t psock_tcp_recvfrom(FAR struct socket *psock, FAR void *buf,
         }
     }
 
-  /* It is okay to block if we need to.  If there is space to receive anything
-   * more, then we will wait to receive the data.  Otherwise return the number
-   * of bytes read from the read-ahead buffer (already in 'ret').
+  /* It is okay to block if we need to.  If there is space to receive
+   * anything more, then we will wait to receive the data.  Otherwise return
+   * the number of bytes read from the read-ahead buffer (already in 'ret').
    */
 
   else
 
-  /* We get here when we we decide that we need to setup the wait for incoming
-   * TCP/IP data.  Just a few more conditions to check:
+  /* We get here when we we decide that we need to setup the wait for
+   * incoming TCP/IP data.  Just a few more conditions to check:
    *
    * 1) Make sure thet there is buffer space to receive additional data
    *    (state.ir_buflen > 0).  This could be zero, for example,  we filled
diff --git a/net/tcp/tcp_sendfile.c b/net/tcp/tcp_sendfile.c
index a488dc7..d9c4640 100644
--- a/net/tcp/tcp_sendfile.c
+++ b/net/tcp/tcp_sendfile.c
@@ -94,16 +94,16 @@
 
 struct sendfile_s
 {
-  FAR struct socket *snd_sock;    /* Points to the parent socket structure */
+  FAR struct socket *snd_sock;             /* Points to the parent socket structure */
   FAR struct devif_callback_s *snd_datacb; /* Data callback */
   FAR struct devif_callback_s *snd_ackcb;  /* ACK callback */
-  FAR struct file   *snd_file;    /* File structure of the input file */
-  sem_t              snd_sem;     /* Used to wake up the waiting thread */
-  off_t              snd_foffset; /* Input file offset */
-  size_t             snd_flen;    /* File length */
-  ssize_t            snd_sent;    /* The number of bytes sent */
-  uint32_t           snd_isn;     /* Initial sequence number */
-  uint32_t           snd_acked;   /* The number of bytes acked */
+  FAR struct file   *snd_file;             /* File structure of the input file */
+  sem_t              snd_sem;              /* Used to wake up the waiting thread */
+  off_t              snd_foffset;          /* Input file offset */
+  size_t             snd_flen;             /* File length */
+  ssize_t            snd_sent;             /* The number of bytes sent */
+  uint32_t           snd_isn;              /* Initial sequence number */
+  uint32_t           snd_acked;            /* The number of bytes acked */
 };
 
 /****************************************************************************
diff --git a/net/udp/udp_sendto_unbuffered.c b/net/udp/udp_sendto_unbuffered.c
index 946b5a6..f9d7385 100644
--- a/net/udp/udp_sendto_unbuffered.c
+++ b/net/udp/udp_sendto_unbuffered.c
@@ -1,36 +1,20 @@
 /****************************************************************************
  * net/udp/udp_sendto_unbuffered.c
  *
- *   Copyright (C) 2007-2009, 2011-2016, 2018-2019 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.
  *
  ****************************************************************************/
 
@@ -273,8 +257,8 @@ static uint16_t sendto_eventhandler(FAR struct net_driver_s *dev,
  ****************************************************************************/
 
 ssize_t psock_udp_sendto(FAR struct socket *psock, FAR const void *buf,
-                         size_t len, int flags, FAR const struct sockaddr *to,
-                         socklen_t tolen)
+                         size_t len, int flags,
+                         FAR const struct sockaddr *to, socklen_t tolen)
 {
   FAR struct udp_conn_s *conn;
   struct sendto_s state;
@@ -486,7 +470,9 @@ ssize_t psock_udp_sendto(FAR struct socket *psock, FAR const void *buf,
       ret = net_timedwait(&state.st_sem, _SO_TIMEOUT(psock->s_sndtimeo));
       if (ret >= 0)
         {
-          /* The result of the sendto operation is the number of bytes transferred */
+          /* The result of the sendto operation is the number of bytes
+           * transferred.
+           */
 
           ret = state.st_sndlen;
         }
diff --git a/net/usrsock/usrsock_conn.c b/net/usrsock/usrsock_conn.c
index 9f86887..0d6261a 100644
--- a/net/usrsock/usrsock_conn.c
+++ b/net/usrsock/usrsock_conn.c
@@ -140,8 +140,8 @@ FAR struct usrsock_conn_s *usrsock_alloc(void)
  * Name: usrsock_free()
  *
  * Description:
- *   Free a usrsock connection structure that is no longer in use. This should
- *   be done by the implementation of close().
+ *   Free a usrsock connection structure that is no longer in use. This
+ *   should be done by the implementation of close().
  *
  ****************************************************************************/
 
@@ -283,10 +283,11 @@ int usrsock_setup_request_callback(FAR struct usrsock_conn_s *conn,
  * Name: usrsock_setup_data_request_callback()
  ****************************************************************************/
 
-int usrsock_setup_data_request_callback(FAR struct usrsock_conn_s *conn,
-                                        FAR struct usrsock_data_reqstate_s *pstate,
-                                        FAR devif_callback_event_t event,
-                                        uint16_t flags)
+int usrsock_setup_data_request_callback(
+      FAR struct usrsock_conn_s *conn,
+      FAR struct usrsock_data_reqstate_s *pstate,
+      FAR devif_callback_event_t event,
+      uint16_t flags)
 {
   pstate->valuelen = 0;
   pstate->valuelen_nontrunc = 0;
diff --git a/sched/pthread/pthread_condsignal.c b/sched/pthread/pthread_condsignal.c
index bd1d190..a7733bd 100644
--- a/sched/pthread/pthread_condsignal.c
+++ b/sched/pthread/pthread_condsignal.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * sched/pthread/pthread_condsignal.c
  *
- *   Copyright (C) 2007-2009, 2012 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.
  *
  ****************************************************************************/
 
@@ -92,13 +77,14 @@ int pthread_cond_signal(FAR pthread_cond_t *cond)
 
       else
         {
-          /* One of my objectives in this design was to make pthread_cond_signal
-           * usable from interrupt handlers.  However, from interrupt handlers,
-           * you cannot take the associated mutex before signaling the condition.
-           * As a result, I think that there could be a race condition with
-           * the following logic which assumes that the if sval < 0 then the
-           * thread is waiting.  Without the mutex, there is no atomic, protected
-           * operation that will guarantee this to be so.
+          /* One of my objectives in this design was to make
+           * pthread_cond_signal() usable from interrupt handlers.  However,
+           * from interrupt handlers, you cannot take the associated mutex
+           * before signaling the condition.  As a result, I think that
+           * there could be a race condition with the following logic which
+           * assumes that the if sval < 0 then the thread is waiting.
+           * Without the mutex, there is no atomic, protected operation that
+           * will guarantee this to be so.
            */
 
           sinfo("sval=%d\n", sval);
diff --git a/sched/pthread/pthread_mutexinit.c b/sched/pthread/pthread_mutexinit.c
index 84d6c1e..0feffc8 100644
--- a/sched/pthread/pthread_mutexinit.c
+++ b/sched/pthread/pthread_mutexinit.c
@@ -1,35 +1,20 @@
 /****************************************************************************
  * sched/pthread/pthread_mutexinit.c
  *
- *   Copyright (C) 2007-2009, 2011, 2016-2017 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.
  *
  ****************************************************************************/
 
@@ -138,7 +123,8 @@ int pthread_mutex_init(FAR pthread_mutex_t *mutex,
       /* Initial internal fields of the mutex */
 
       mutex->flink  = NULL;
-      mutex->flags  = (robust == PTHREAD_MUTEX_ROBUST ? _PTHREAD_MFLAGS_ROBUST : 0);
+      mutex->flags  = (robust == PTHREAD_MUTEX_ROBUST ?
+                       _PTHREAD_MFLAGS_ROBUST : 0);
 #endif
 
 #ifdef CONFIG_PTHREAD_MUTEX_TYPES