Check return from nxsem_wait_initialize()

Resolution of Issue 619 will require multiple steps, this part of the first step in that resolution:  Every call to nxsem_wait_uninterruptible() must handle the return value from nxsem_wait_uninterruptible properly.  This commit is only for those files under drivers/pipes and drivers/wireless.
This commit is contained in:
Gregory Nutt 2020-03-31 13:59:25 -06:00 committed by Abdelatif Guettouche
parent 836fef358b
commit 986e594563
3 changed files with 218 additions and 142 deletions
drivers
pipes
wireless

@ -1,36 +1,20 @@
/****************************************************************************
* drivers/pipes/pipe_common.c
*
* Copyright (C) 2008-2009, 2011, 2015-2016, 2018 Gregory Nutt. All
* rights reserved.
* Author: Gregory Nutt <gnutt@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.
*
****************************************************************************/
@ -79,12 +63,6 @@
# define pipe_dumpbuffer(m,a,n)
#endif
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static void pipecommon_semtake(sem_t *sem);
/****************************************************************************
* Private Functions
****************************************************************************/
@ -93,9 +71,9 @@ static void pipecommon_semtake(sem_t *sem);
* Name: pipecommon_semtake
****************************************************************************/
static void pipecommon_semtake(FAR sem_t *sem)
static int pipecommon_semtake(FAR sem_t *sem)
{
nxsem_wait_uninterruptible(sem);
return nxsem_wait_uninterruptible(sem);
}
/****************************************************************************
@ -201,7 +179,8 @@ int pipecommon_open(FAR struct file *filep)
DEBUGASSERT(dev != NULL);
/* Make sure that we have exclusive access to the device structure. The
* nxsem_wait() call should fail only if we are awakened by a signal.
* nxsem_wait() call should fail if we are awakened by a signal or if the
* thread was canceled.
*/
ret = nxsem_wait(&dev->d_bfsem);
@ -232,8 +211,9 @@ int pipecommon_open(FAR struct file *filep)
{
dev->d_nwriters++;
/* If this this is the first writer, then the read semaphore indicates the
* number of readers waiting for the first writer. Wake them all up.
/* If this this is the first writer, then the read semaphore indicates
* the number of readers waiting for the first writer. Wake them all
* up.
*/
if (dev->d_nwriters == 1)
@ -276,8 +256,8 @@ int pipecommon_open(FAR struct file *filep)
ret = nxsem_wait(&dev->d_rdsem);
if (ret < 0)
{
/* The nxsem_wait() call should fail only if we are awakened by
* a signal.
/* The nxsem_wait() call should fail if we are awakened by a
* signal or if the task is canceled.
*/
ferr("ERROR: nxsem_wait failed: %d\n", ret);
@ -301,6 +281,7 @@ int pipecommon_close(FAR struct file *filep)
FAR struct inode *inode = filep->f_inode;
FAR struct pipe_dev_s *dev = inode->i_private;
int sval;
int ret;
DEBUGASSERT(dev && filep->f_inode->i_crefs > 0);
@ -309,7 +290,13 @@ int pipecommon_close(FAR struct file *filep)
* I've never seen anyone check that.
*/
pipecommon_semtake(&dev->d_bfsem);
ret = pipecommon_semtake(&dev->d_bfsem);
if (ret < 0)
{
/* The close will not be performed if the task was canceled */
return ret;
}
/* Decrement the number of references on the pipe. Check if there are
* still outstanding references to the pipe.
@ -325,8 +312,8 @@ int pipecommon_close(FAR struct file *filep)
if ((filep->f_oflags & O_WROK) != 0)
{
/* If there are no longer any writers on the pipe, then notify all of the
* waiting readers that they must return end-of-file.
/* If there are no longer any writers on the pipe, then notify all
* of the waiting readers that they must return end-of-file.
*/
if (--dev->d_nwriters <= 0)
@ -424,6 +411,10 @@ ssize_t pipecommon_read(FAR struct file *filep, FAR char *buffer, size_t len)
ret = nxsem_wait(&dev->d_bfsem);
if (ret < 0)
{
/* May fail because a signal was received or if the task was
* canceled.
*/
return ret;
}
@ -456,6 +447,10 @@ ssize_t pipecommon_read(FAR struct file *filep, FAR char *buffer, size_t len)
if (ret < 0 || (ret = nxsem_wait(&dev->d_bfsem)) < 0)
{
/* May fail because a signal was received or if the task was
* canceled.
*/
return ret;
}
}
@ -527,16 +522,16 @@ ssize_t pipecommon_write(FAR struct file *filep, FAR const char *buffer,
}
/* At present, this method cannot be called from interrupt handlers. That
* is because it calls nxsem_wait (via pipecommon_semtake below) and
* nxsem_wait cannot be called from interrupt level. This actually
* happens fairly commonly IF [a-z]err() is called from interrupt handlers
* and stdout is being redirected via a pipe. In that case, the debug
* output will try to go out the pipe (interrupt handlers should use the
* _err() APIs).
* is because it calls nxsem_wait() and nxsem_wait() cannot be called from
* interrupt level. This actually happens fairly commonly IF [a-z]err()
* is called from interrupt handlers and stdout is being redirected via a
* pipe. In that case, the debug output will try to go out the pipe
* (interrupt handlers should use the _err() APIs).
*
* On the other hand, it would be very valuable to be able to feed the pipe
* from an interrupt handler! TODO: Consider disabling interrupts instead
* of taking semaphores so that pipes can be written from interrupt handlers
* of taking semaphores so that pipes can be written from interrupt
* handlers.
*/
DEBUGASSERT(up_interrupt_context() == false);
@ -546,6 +541,10 @@ ssize_t pipecommon_write(FAR struct file *filep, FAR const char *buffer,
ret = nxsem_wait(&dev->d_bfsem);
if (ret < 0)
{
/* May fail because a signal was received or if the task was
* canceled.
*/
return ret;
}
@ -626,13 +625,23 @@ ssize_t pipecommon_write(FAR struct file *filep, FAR const char *buffer,
return nwritten;
}
/* There is more to be written.. wait for data to be removed from the pipe */
/* There is more to be written.. wait for data to be removed fro
* the pipe
*/
sched_lock();
nxsem_post(&dev->d_bfsem);
pipecommon_semtake(&dev->d_wrsem);
ret = nxsem_wait(&dev->d_wrsem);
sched_unlock();
pipecommon_semtake(&dev->d_bfsem);
if (ret < 0 || (ret = nxsem_wait(&dev->d_bfsem)) < 0)
{
/* Either call nxsem_wait may fail because a signal was
* received or if the task was canceled.
*/
return nwritten == 0 ? (ssize_t)ret : nwritten;
}
}
}
}
@ -648,14 +657,19 @@ int pipecommon_poll(FAR struct file *filep, FAR struct pollfd *fds,
FAR struct pipe_dev_s *dev = inode->i_private;
pollevent_t eventset;
pipe_ndx_t nbytes;
int ret = OK;
int ret;
int i;
DEBUGASSERT(dev && fds);
/* Are we setting up the poll? Or tearing it down? */
pipecommon_semtake(&dev->d_bfsem);
ret = pipecommon_semtake(&dev->d_bfsem);
if (ret < 0)
{
return ret;
}
if (setup)
{
/* This is a request to set up the poll. Find an available
@ -778,7 +792,11 @@ int pipecommon_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
}
#endif
pipecommon_semtake(&dev->d_bfsem);
ret = pipecommon_semtake(&dev->d_bfsem);
if (ret < 0)
{
return ret;
}
switch (cmd)
{
@ -851,6 +869,7 @@ int pipecommon_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
break;
default:
ret = -ENOTTY;
break;
}

@ -39,6 +39,7 @@
* See "GS2200MS2W Adapter Command Reference Guide" for the explanation
* of AT commands. You can find the document at:
* https://www.telit.com/m2m-iot-products/wifi-bluetooth-modules/wi-fi-gs2200m/
*
****************************************************************************/
/****************************************************************************
@ -672,9 +673,9 @@ errout:
* Name: gs2200m_lock
****************************************************************************/
static void gs2200m_lock(FAR struct gs2200m_dev_s *dev)
static int gs2200m_lock(FAR struct gs2200m_dev_s *dev)
{
nxsem_wait_uninterruptible(&dev->dev_sem);
return nxsem_wait_uninterruptible(&dev->dev_sem);
}
/****************************************************************************
@ -713,6 +714,7 @@ static ssize_t gs2200m_read(FAR struct file *filep, FAR char *buffer,
{
FAR struct inode *inode;
FAR struct gs2200m_dev_s *dev;
int ret;
DEBUGASSERT(filep);
inode = filep->f_inode;
@ -722,7 +724,15 @@ static ssize_t gs2200m_read(FAR struct file *filep, FAR char *buffer,
ASSERT(1 == len);
gs2200m_lock(dev);
ret = nxsem_wait(dev);
if (ret < 0)
{
/* Return if a signal is received or if the the task was canceled
* while we were waiting.
*/
return ret;
}
ASSERT(0 < _notif_q_count(dev));
char cid = _notif_q_pop(dev);
@ -744,7 +754,7 @@ static ssize_t gs2200m_read(FAR struct file *filep, FAR char *buffer,
static ssize_t gs2200m_write(FAR struct file *filep, FAR const char *buffer,
size_t len)
{
return 0;
return 0; /* REVISIT: Zero is not a legal return value from write() */
}
/****************************************************************************
@ -2528,7 +2538,13 @@ static int gs2200m_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
/* Lock the device */
gs2200m_lock(dev);
ret = gs2200m_lock(dev);
if (ret < 0)
{
/* Return only if the task was canceled */
return ret;
}
/* Disable gs2200m irq to poll dready */
@ -2649,7 +2665,13 @@ static int gs2200m_poll(FAR struct file *filep, FAR struct pollfd *fds,
DEBUGASSERT(inode && inode->i_private);
dev = (FAR struct gs2200m_dev_s *)inode->i_private;
gs2200m_lock(dev);
ret = gs2200m_lock(dev);
if (ret < 0)
{
/* Return if the task was canceled */
return ret;
}
/* Are we setting up the poll? Or tearing it down? */
@ -2708,11 +2730,22 @@ static void gs2200m_irq_worker(FAR void *arg)
char c_cid;
int n;
int ec;
int ret;
DEBUGASSERT(arg != NULL);
dev = (FAR struct gs2200m_dev_s *)arg;
gs2200m_lock(dev);
do
{
ret = gs2200m_lock(dev);
/* The only failure would be if the worker thread were canceled. That
* is very unlikely, however.
*/
DEBUGASSERT(ret == OK || ret == -ECANCELED);
}
while (ret < 0);
n = dev->lower->dready(&ec);
wlinfo("== start (dready=%d, ec=%d) \n", n, ec);
@ -2893,6 +2926,7 @@ static int gs2200m_start(FAR struct gs2200m_dev_s *dev)
#if CONFIG_WL_GS2200M_LOGLEVEL > 0
/* Set log level */
t = gs2200m_set_loglevel(dev, CONFIG_WL_GS2200M_LOGLEVEL);
ASSERT(TYPE_OK == t);
#endif

@ -1,35 +1,20 @@
/****************************************************************************
* drivers/wireless/spirit/drivers/spirit_netdev.c
*
* Copyright (C) 2017 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@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.
*
****************************************************************************/
@ -53,11 +38,11 @@
* interrupt handling, but the primary things are: (1) receipt of incoming
* packets, and (2) handling of the completion of TX transfers.
*
* The receipt of the incoming packet is handled on the HP work worker thread.
* The received packet is extracted from the hardware, saved in an I/O
* buffer (IOB), and queued in the RX packet queue. Processing of the
* received packet is scheduled to occur on the LP worker thread where each IOB
* removed from RX packet queue is passed to the network via
* The receipt of the incoming packet is handled on the HP work worker
* thread. The received packet is extracted from the hardware, saved in an
* I/O buffer (IOB), and queued in the RX packet queue. Processing of the
* received packet is scheduled to occur on the LP worker thread where each
* IOB removed from RX packet queue is passed to the network via
* sixlowpan_input().
*
* The entire network logic runs on the LP worker thread. If the receipt of
@ -72,12 +57,12 @@
* previous transfer and that the hardware is ready to send another packet.
*
* In this way, the interrupt handling and TX processing is serialized on
* the HP worker thread and no special interlocking is required. Network level
* work is similar serialized on the LP worker thread (and also via the network
* locking mechanism). So the only real interactions between the logic
* running on the LP and HP worker threads is in the access to the RX and TX
* packet queues. Semaphore protection is necessary while accessing these
* queues.
* the HP worker thread and no special interlocking is required. Network
* level work is similar serialized on the LP worker thread (and also via
* the network locking mechanism). So the only real interactions between
* the logic running on the LP and HP worker threads is in the access to the
* RX and TX packet queues. Semaphore protection is necessary while
* accessing these queues.
*
* A special case is the TX timeout which must be handled on the HP work
* queue since it will reset the spirit interface.
@ -99,7 +84,8 @@
* for example, disabling the Spirit interrupt tears down the the entire
* interrupt setup so, for example, any interrupts that are received while
* interrupts are disable, aka torn down, will be lost. Hence, it may be
* necessary to process pending interrupts whenever interrupts are re-enabled.
* necessary to process pending interrupts whenever interrupts are re-
* enabled.
*/
/****************************************************************************
@ -260,13 +246,13 @@ enum spirit_driver_state_e
/* SPIRIT1 device instance
*
* Make sure that struct ieee802154_radio_s remains first. If not it will break the
* code
* Make sure that struct ieee802154_radio_s remains first. If not it will
* break the code
*/
struct spirit_driver_s
{
struct radio_driver_s radio; /* Interface understood by the network */
struct radio_driver_s radio; /* Interface understood by the network */
struct spirit_library_s spirit; /* Spirit library state */
FAR const struct spirit_lower_s *lower; /* Low-level MCU-specific support */
FAR struct pktradio_metadata_s *txhead; /* Head of pending TX transfers */
@ -389,7 +375,7 @@ static const struct radio_init_s g_radio_init =
static const struct spirit_pktstack_init_s g_pktstack_init =
{
SPIRIT_SYNC_WORD, /* syncword selected in board.h */
SPIRIT_PREAMBLE_LENGTH, /* premblen selected in board.h*/
SPIRIT_PREAMBLE_LENGTH, /* premblen selected in board.h */
SPIRIT_SYNC_LENGTH, /* synclen selected in board.h */
PKT_LENGTH_VAR, /* fixvarlen variable packet length */
PKT_LENGTH_WIDTH, /* pktlenwidth from CONFIG_SPIRIT_PKTLEN */
@ -486,7 +472,21 @@ static struct spirit_pktstack_address_s g_addrinit =
static void spirit_rxlock(FAR struct spirit_driver_s *priv)
{
nxsem_wait_uninterruptible(&priv->rxsem);
int ret;
/* The only error that can be reported by nxsem_wait_uninterruptible() is
* ECANCELED if the the thread is canceled. All of the work runs on the
* LP work thread, however. It is very unlikely that the LP worker thread
* will be canceled and, if so, it should finish the work in progress
* before dying anyway.
*/
do
{
ret = nxsem_wait_uninterruptible(&priv->rxsem);
DEBUGASSERT(ret == 0 || ret == -ECANCELED);
}
while (ret < 0);
}
/****************************************************************************
@ -524,7 +524,21 @@ static inline void spirit_rxunlock(FAR struct spirit_driver_s *priv)
static void spirit_txlock(FAR struct spirit_driver_s *priv)
{
nxsem_wait_uninterruptible(&priv->txsem);
int ret;
/* The only error that can be reported by nxsem_wait_uninterruptible() is
* ECANCELED if the the thread is canceled. All of the work runs on the
* LP work thread, however. It is very unlikely that the LP worker thread
* will be canceled and, if so, it should finish the work in progress
* before dying anyway.
*/
do
{
ret = nxsem_wait_uninterruptible(&priv->txsem);
DEBUGASSERT(ret == 0 || ret == -ECANCELED);
}
while (ret < 0);
}
/****************************************************************************
@ -728,12 +742,13 @@ static void spirit_transmit_work(FAR void *arg)
wlinfo("txhead=%p state=%u\n", priv->txhead, priv->state);
/* Take the TX packet queue lock to assure that it is not currently being
* modified on the LP worker thread. NOTE that it is not harmful to hold the
* TX packet queue lock throughout this function; the LP worker thread cannot
* run until this completes.
* modified on the LP worker thread. NOTE that it is not harmful to hold
* the TX packet queue lock throughout this function; the LP worker thread
* cannot run until this completes.
*/
spirit_txlock(priv);
while (priv->txhead != NULL && priv->state == DRIVER_STATE_IDLE)
{
/* Peek at the packet at the head of the TX queue */
@ -982,8 +997,8 @@ static void spirit_schedule_transmit_work(FAR struct spirit_driver_s *priv)
static int spirit_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.
*
* REVISIT: Should we halt polling if there are packets in flight.
*/
@ -1021,9 +1036,10 @@ static void spirit_receive_work(FAR void *arg)
* queued asynchronously by interrupt level logic.
*/
spirit_rxlock(priv);
while (priv->rxhead != NULL)
{
spirit_rxlock(priv);
/* Remove the contained IOB from the RX queue */
pktmeta = priv->rxhead;
@ -1070,13 +1086,7 @@ static void spirit_receive_work(FAR void *arg)
*/
pktradio_metadata_free(pktmeta);
/* Get exclusive access as needed at the top of the loop */
spirit_rxlock(priv);
}
spirit_rxunlock(priv);
}
/****************************************************************************
@ -1096,7 +1106,8 @@ static void spirit_receive_work(FAR void *arg)
*
****************************************************************************/
static inline void spirit_schedule_receive_work(FAR struct spirit_driver_s *priv)
static inline void
spirit_schedule_receive_work(FAR struct spirit_driver_s *priv)
{
/* Schedule to perform the RX processing on the worker thread. */
@ -1332,8 +1343,8 @@ static void spirit_interrupt_work(FAR void *arg)
irqstatus.IRQ_RX_FIFO_ALMOST_FULL = 0;
/* There should be a packet buffer that was allocated when the data sync
* interrupt was processed.
/* There should be a packet buffer that was allocated when the data
* sync interrupt was processed.
*/
iob = priv->rxbuffer;
@ -1397,7 +1408,8 @@ static void spirit_interrupt_work(FAR void *arg)
{
/* Read the remainder of the packet into the I/O buffer */
DEBUGVERIFY(spirit_fifo_read(spirit, &iob->io_data[offset], count));
DEBUGVERIFY(spirit_fifo_read(spirit, &iob->io_data[offset],
count));
iob->io_len = spirit_pktstack_get_rxpktlen(spirit);
iob->io_offset = 0;
iob->io_pktlen = iob->io_len;
@ -1408,8 +1420,9 @@ static void spirit_interrupt_work(FAR void *arg)
DEBUGVERIFY(spirit_command(spirit, CMD_FLUSHRXFIFO));
priv->state = DRIVER_STATE_IDLE;
/* Create the packet meta data and forward to the network. This
* must be done on the LP worker thread with the network locked.
/* Create the packet meta data and forward to the network.
* This must be done on the LP worker thread with the network
* locked.
*/
pktmeta = pktradio_metadata_allocate();
@ -1485,8 +1498,8 @@ static void spirit_interrupt_work(FAR void *arg)
wlinfo("RX FIFO almost full\n");
/* There should be a packet buffer that was allocated when the data sync
* interrupt was processed.
/* There should be a packet buffer that was allocated when the data
* sync interrupt was processed.
*/
if (priv->rxbuffer != NULL)
@ -1532,7 +1545,8 @@ static void spirit_interrupt_work(FAR void *arg)
{
/* Read more of the packet into the I/O buffer */
DEBUGVERIFY(spirit_fifo_read(spirit, &iob->io_data[offset], count));
DEBUGVERIFY(spirit_fifo_read(spirit, &iob->io_data[offset],
count));
iob->io_len = count + offset;
iob->io_offset = 0;
iob->io_pktlen = iob->io_len;
@ -1754,7 +1768,8 @@ static void spirit_txtimeout_expiry(int argc, wdparm_t arg, ...)
static void spirit_txpoll_work(FAR void *arg)
{
FAR struct spirit_driver_s *priv = (FAR struct spirit_driver_s *)arg;
FAR struct spirit_driver_s *priv =
(FAR struct spirit_driver_s *)arg;
/* Lock the network and serialize driver operations if necessary.
* NOTE: Serialization is only required in the case where the driver work
@ -1784,7 +1799,8 @@ static void spirit_txpoll_work(FAR void *arg)
/* Perform the periodic poll */
priv->needpoll = false;
devif_timer(&priv->radio.r_dev, SPIRIT_WDDELAY, spirit_txpoll_callback);
devif_timer(&priv->radio.r_dev, SPIRIT_WDDELAY,
spirit_txpoll_callback);
/* Setup the watchdog poll timer again */
@ -1851,7 +1867,8 @@ static void spirit_txpoll_expiry(int argc, wdparm_t arg, ...)
static int spirit_ifup(FAR struct net_driver_s *dev)
{
FAR struct spirit_driver_s *priv = (FAR struct spirit_driver_s *)dev->d_private;
FAR struct spirit_driver_s *priv =
(FAR struct spirit_driver_s *)dev->d_private;
FAR struct spirit_library_s *spirit;
int ret;
@ -1968,7 +1985,8 @@ error_with_ifalmostup:
static int spirit_ifdown(FAR struct net_driver_s *dev)
{
FAR struct spirit_driver_s *priv = (FAR struct spirit_driver_s *)dev->d_private;
FAR struct spirit_driver_s *priv =
(FAR struct spirit_driver_s *)dev->d_private;
FAR struct spirit_library_s *spirit;
int ret = OK;
@ -2061,7 +2079,8 @@ static int spirit_ifdown(FAR struct net_driver_s *dev)
static int spirit_txavail(FAR struct net_driver_s *dev)
{
FAR struct spirit_driver_s *priv = (FAR struct spirit_driver_s *)dev->d_private;
FAR struct spirit_driver_s *priv =
(FAR struct spirit_driver_s *)dev->d_private;
/* Schedule to serialize the poll on the LP worker thread. */
@ -2086,7 +2105,8 @@ static int spirit_txavail(FAR struct net_driver_s *dev)
****************************************************************************/
#ifdef CONFIG_NET_MCASTGROUP
static int spirit_addmac(FAR struct net_driver_s *dev, FAR const uint8_t *mac)
static int spirit_addmac(FAR struct net_driver_s *dev,
FAR const uint8_t *mac)
{
return -ENOSYS;
}
@ -2252,7 +2272,8 @@ static int spirit_ioctl(FAR struct net_driver_s *dev, int cmd,
static int spirit_get_mhrlen(FAR struct radio_driver_s *netdev,
FAR const void *meta)
{
DEBUGASSERT(netdev != NULL && netdev->r_dev.d_private != NULL && meta != NULL);
DEBUGASSERT(netdev != NULL && netdev->r_dev.d_private != NULL &&
meta != NULL);
/* There is no header on the Spirit radio payload */
@ -2683,7 +2704,8 @@ int spirit_hw_initialize(FAR struct spirit_driver_s *priv,
SQI_ABOVE_THRESHOLD);
if (ret < 0)
{
wlerr("ERROR: spirit_timer_set_rxtimeout_stopcondition failed: %d\n", ret);
wlerr("ERROR: spirit_timer_set_rxtimeout_stopcondition failed: %d\n",
ret);
return ret;
}
@ -2773,7 +2795,8 @@ int spirit_netdev_initialize(FAR struct spi_dev_s *spi,
/* Allocate a driver state structure instance */
priv = (FAR struct spirit_driver_s *)kmm_zalloc(sizeof(struct spirit_driver_s));
priv = (FAR struct spirit_driver_s *)
kmm_zalloc(sizeof(struct spirit_driver_s));
if (priv == NULL)
{
wlerr("ERROR: Failed to allocate device structure\n");
@ -2830,9 +2853,9 @@ int spirit_netdev_initialize(FAR struct spi_dev_s *spi,
}
#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->radio.r_dev.d_buf = g_iobuffer.rb_buf;