"Uninterruptible" semaphore waits must return when canceled.
nxsem_timedwait_uninterruptible() must return -ECANCELED if the thread is canceled: include/nuttx/semaphore.h: Return if nxsem_wait() returns ECANCELED meaning that the thread waiting for the semaphore has been canceled. sched/semaphore/sem_timedwait.c: Same change (the inline version is in semaphore.h, the non-inlined version is in sem_tickwait.c). drivers/sensors/lps25h.c and drivers/wireless/bluetooth/bt_uart_bcm4343x.c: Make sure that the caller deals correctly with the -ECANCELED return value. Refer to issue 619.
This commit is contained in:
parent
2b139625bb
commit
0558aa0a78
@ -69,8 +69,8 @@
|
||||
* for conversion times:
|
||||
*
|
||||
* Typical conversion time ≈ 62*(Pavg+Tavg) + 975 μs
|
||||
* ex: Tavg = 64; Pavg = 512; Typ. conversation time ≈ 36.7 ms (compatible with
|
||||
* ODT=25 Hz)
|
||||
* ex: Tavg = 64; Pavg = 512; Typ. conversation time ≈ 36.7 ms
|
||||
* (compatible with ODT=25 Hz)
|
||||
* ex: Tavg = 32; Pavg = 128; Typ. conversation time ≈ 10.9 ms
|
||||
* The formula is accurate within +/- 3% at room temperature
|
||||
*
|
||||
@ -155,10 +155,10 @@ enum LPS25H_RES_CONF_AVG_TEMP
|
||||
enum LPS25H_CTRL_REG1_ODR
|
||||
{
|
||||
CTRL_REG1_ODR_ONE_SHOT = 0,
|
||||
CTRL_REG1_ODR_1Hz,
|
||||
CTRL_REG1_ODR_7Hz,
|
||||
CTRL_REG1_ODR_12_5Hz,
|
||||
CTRL_REG1_ODR_25Hz
|
||||
CTRL_REG1_ODR_1HZ,
|
||||
CTRL_REG1_ODR_7HZ,
|
||||
CTRL_REG1_ODR_12_5HZ,
|
||||
CTRL_REG1_ODR_25HZ
|
||||
};
|
||||
|
||||
enum LPS25H_CTRL_REG4_P1
|
||||
@ -196,9 +196,9 @@ enum LPS25H_INT_CFG_OP
|
||||
LIR = 0x4
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
************************************************************************************/
|
||||
****************************************************************************/
|
||||
|
||||
static int lps25h_open(FAR struct file *filep);
|
||||
static int lps25h_close(FAR struct file *filep);
|
||||
@ -413,7 +413,7 @@ static ssize_t lps25h_read(FAR struct file *filep, FAR char *buffer,
|
||||
{
|
||||
/* This interface is mainly intended for easy debugging in nsh. */
|
||||
|
||||
length = snprintf(buffer, buflen, "%u\n", data.pressure_Pa);
|
||||
length = snprintf(buffer, buflen, "%u\n", data.pressure_pa);
|
||||
if (length > buflen)
|
||||
{
|
||||
length = buflen;
|
||||
@ -486,7 +486,7 @@ static int lps25h_configure_dev(FAR struct lps25h_dev_s *dev)
|
||||
/* Write CTRL_REG1 to turn device on */
|
||||
|
||||
ret = lps25h_write_reg8(dev, LPS25H_CTRL_REG1,
|
||||
LPS25H_PD | (CTRL_REG1_ODR_1Hz << 4));
|
||||
LPS25H_PD | (CTRL_REG1_ODR_1HZ << 4));
|
||||
|
||||
return ret;
|
||||
}
|
||||
@ -570,7 +570,7 @@ static int lps25h_one_shot(FAR struct lps25h_dev_s *dev)
|
||||
{
|
||||
/* Some unknown mystery error */
|
||||
|
||||
DEBUGASSERT(false);
|
||||
DEBUGASSERT(ret == -ECANCELED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
@ -635,10 +635,13 @@ static int lps25h_read_pressure(FAR struct lps25h_dev_s *dev,
|
||||
|
||||
/* Convert to more usable format. */
|
||||
|
||||
pres->pressure_int_hP = pres_res / LPS25H_PRESSURE_INTERNAL_DIVIDER;
|
||||
pres->pressure_Pa = (uint64_t)pres_res * 100000 / LPS25H_PRESSURE_INTERNAL_DIVIDER;
|
||||
pres->raw_data = pres_res;
|
||||
lps25h_dbg("Pressure: %u Pa\n", pres->pressure_Pa);
|
||||
pres->pressure_int_hp =
|
||||
pres_res / LPS25H_PRESSURE_INTERNAL_DIVIDER;
|
||||
pres->pressure_pa = (uint64_t)
|
||||
pres_res * 100000 / LPS25H_PRESSURE_INTERNAL_DIVIDER;
|
||||
pres->raw_data = pres_res;
|
||||
|
||||
lps25h_dbg("Pressure: %u Pa\n", pres->pressure_pa);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
@ -107,7 +107,6 @@ extern const uint8_t g_bt_firmware_hcd[];
|
||||
|
||||
static void hciuart_cb(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR void *param)
|
||||
|
||||
{
|
||||
FAR sem_t *rxsem = (FAR sem_t *)param;
|
||||
|
||||
@ -138,7 +137,6 @@ static int uartwriteconf(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR sem_t *rxsem,
|
||||
FAR const uint8_t *dout, uint32_t doutl,
|
||||
FAR const uint8_t *cmp, uint32_t maxl)
|
||||
|
||||
{
|
||||
int ret;
|
||||
int gotlen = 0;
|
||||
@ -183,18 +181,18 @@ static int uartwriteconf(FAR const struct btuart_lowerhalf_s *lower,
|
||||
}
|
||||
|
||||
ret = nxsem_timedwait_uninterruptible(rxsem, &abstime);
|
||||
if (ret == -ETIMEDOUT)
|
||||
if (ret < 0)
|
||||
{
|
||||
/* We didn't receive enough message, so fall out */
|
||||
|
||||
wlerr("Response timed out\n");
|
||||
wlerr("Response timed out: %d\n", ret);
|
||||
goto exit_uartwriteconf;
|
||||
}
|
||||
|
||||
ret = lower->read(lower, &din[gotlen], maxl - gotlen);
|
||||
if (ret < 0)
|
||||
{
|
||||
wlerr("Couldn't read\n");
|
||||
wlerr("Couldn't read: %d\n", ret);
|
||||
ret = -ECOMM;
|
||||
goto exit_uartwriteconf;
|
||||
}
|
||||
@ -228,7 +226,6 @@ exit_uartwriteconf_nofree:
|
||||
|
||||
static int set_baudrate(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR sem_t *rxsem, int targetspeed)
|
||||
|
||||
{
|
||||
int ret;
|
||||
uint8_t baudrate_cmd[] =
|
||||
@ -268,7 +265,6 @@ static int set_baudrate(FAR const struct btuart_lowerhalf_s *lower,
|
||||
****************************************************************************/
|
||||
|
||||
static int load_bcm4343x_firmware(FAR const struct btuart_lowerhalf_s *lower)
|
||||
|
||||
{
|
||||
FAR uint8_t *rp = (FAR uint8_t *)g_bt_firmware_hcd;
|
||||
int ret = OK;
|
||||
@ -282,24 +278,28 @@ static int load_bcm4343x_firmware(FAR const struct btuart_lowerhalf_s *lower)
|
||||
|
||||
const uint8_t command_resp[] =
|
||||
{
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_write_command, g_hcd_command_byte2, 0x00
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_write_command, g_hcd_command_byte2,
|
||||
0x00
|
||||
};
|
||||
|
||||
const uint8_t launch_resp[] =
|
||||
{
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_launch_command, g_hcd_command_byte2, 0x00
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_launch_command, g_hcd_command_byte2,
|
||||
0x00
|
||||
};
|
||||
|
||||
const uint8_t download_resp[] =
|
||||
{
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_patchram_command, g_hcd_command_byte2, 0x00
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_patchram_command, g_hcd_command_byte2,
|
||||
0x00
|
||||
};
|
||||
|
||||
/* Command to switch the chip into download mode */
|
||||
|
||||
const uint8_t enter_download_mode[] =
|
||||
{
|
||||
0x01, g_hcd_patchram_command, g_hcd_command_byte2, 0x00
|
||||
0x01, g_hcd_patchram_command, g_hcd_command_byte2,
|
||||
0x00
|
||||
};
|
||||
|
||||
/* Let's temporarily connect to the hci uart rx callback so we can get data */
|
||||
|
@ -1,35 +1,20 @@
|
||||
/****************************************************************************
|
||||
* include/nuttx/semaphore.h
|
||||
*
|
||||
* Copyright (C) 2014-2017, 2020 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -174,10 +159,10 @@ int nxsem_init(FAR sem_t *sem, int pshared, unsigned int value);
|
||||
* Description:
|
||||
* This function is used to destroy the un-named semaphore indicated by
|
||||
* 'sem'. Only a semaphore that was created using nxsem_init() may be
|
||||
* destroyed using nxsem_destroy(); the effect of calling nxsem_destroy() with
|
||||
* a named semaphore is undefined. The effect of subsequent use of the
|
||||
* semaphore sem is undefined until sem is re-initialized by another call
|
||||
* to nxsem_init().
|
||||
* destroyed using nxsem_destroy(); the effect of calling nxsem_destroy()
|
||||
* with a named semaphore is undefined. The effect of subsequent use of
|
||||
* the semaphore sem is undefined until sem is re-initialized by another
|
||||
* call to nxsem_init().
|
||||
*
|
||||
* The effect of destroying a semaphore upon which other processes are
|
||||
* currently blocked is undefined.
|
||||
@ -290,6 +275,7 @@ int nxsem_trywait(FAR sem_t *sem);
|
||||
* expired.
|
||||
* EDEADLK A deadlock condition was detected.
|
||||
* EINTR A signal interrupted this function.
|
||||
* ECANCELED May be returned if the thread is canceled while waiting.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -316,8 +302,10 @@ int nxsem_timedwait(FAR sem_t *sem, FAR const struct timespec *abstime);
|
||||
* Returned Value:
|
||||
* This is an internal OS interface, not available to applications, and
|
||||
* hence follows the NuttX internal error return policy: Zero (OK) is
|
||||
* returned on success. A negated errno value is returned on failure.
|
||||
* -ETIMEDOUT is returned on the timeout condition.
|
||||
* returned on success. A negated errno value is returned on failure:
|
||||
*
|
||||
* -ETIMEDOUT is returned on the timeout condition.
|
||||
* -ECANCELED may be returned if the thread is canceled while waiting.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -528,8 +516,8 @@ int sem_setprotocol(FAR sem_t *sem, int protocol);
|
||||
* Name: nxsem_wait_uninterruptible
|
||||
*
|
||||
* Description:
|
||||
* This function is wrapped version of nxsem_wait(), which is uninterruptible
|
||||
* and convenient for use.
|
||||
* This function is wrapped version of nxsem_wait(), which is
|
||||
* uninterruptible and convenient for use.
|
||||
*
|
||||
* Parameters:
|
||||
* sem - Semaphore descriptor.
|
||||
@ -578,6 +566,7 @@ int nxsem_wait_uninterruptible(FAR sem_t *sem);
|
||||
* ETIMEDOUT The semaphore could not be locked before the specified timeout
|
||||
* expired.
|
||||
* EDEADLK A deadlock condition was detected.
|
||||
* ECANCELED May be returned if the thread is canceled while waiting.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -594,7 +583,7 @@ static inline int
|
||||
|
||||
ret = nxsem_timedwait(sem, abstime);
|
||||
}
|
||||
while (ret == -EINTR || ret == -ECANCELED);
|
||||
while (ret == -EINTR);
|
||||
|
||||
return ret;
|
||||
}
|
||||
@ -621,14 +610,19 @@ int nxsem_timedwait_uninterruptible(FAR sem_t *sem,
|
||||
* to sem_trywait().
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success. A negated errno value is returned
|
||||
* on failure. -ETIMEDOUT is returned on the timeout condition.
|
||||
* This is an internal OS interface, not available to applications, and
|
||||
* hence follows the NuttX internal error return policy: Zero (OK) is
|
||||
* returned on success. A negated errno value is returned on failure:
|
||||
*
|
||||
* -ETIMEDOUT is returned on the timeout condition.
|
||||
* -ECANCELED may be returned if the thread is canceled while waiting.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_HAVE_INLINE
|
||||
static inline int
|
||||
nxsem_tickwait_uninterruptible(FAR sem_t *sem, clock_t start, uint32_t delay)
|
||||
nxsem_tickwait_uninterruptible(FAR sem_t *sem, clock_t start,
|
||||
uint32_t delay)
|
||||
{
|
||||
int ret;
|
||||
|
||||
@ -638,7 +632,7 @@ static inline int
|
||||
|
||||
ret = nxsem_tickwait(sem, start, delay);
|
||||
}
|
||||
while (ret == -EINTR || ret == -ECANCELED);
|
||||
while (ret == -EINTR);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
@ -62,8 +62,8 @@ typedef struct lps25h_temper_data_s
|
||||
|
||||
typedef struct lps25h_pressure_data_s
|
||||
{
|
||||
uint32_t pressure_int_hP;
|
||||
uint32_t pressure_Pa;
|
||||
uint32_t pressure_int_hp;
|
||||
uint32_t pressure_pa;
|
||||
uint32_t raw_data;
|
||||
} lps25h_pressure_data_t;
|
||||
|
||||
|
@ -1,35 +1,20 @@
|
||||
/****************************************************************************
|
||||
* sched/semaphore/sem_tickwait.c
|
||||
*
|
||||
* Copyright (C) 2015-2017, 2020 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -176,6 +161,7 @@ errout_with_irqdisabled:
|
||||
rtcb->waitdog = NULL;
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxsem_tickwait_uninterruptible
|
||||
*
|
||||
@ -194,8 +180,12 @@ errout_with_irqdisabled:
|
||||
* to sem_trywait().
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero (OK) is returned on success. A negated errno value is returned
|
||||
* on failure. -ETIMEDOUT is returned on the timeout condition.
|
||||
* This is an internal OS interface, not available to applications, and
|
||||
* hence follows the NuttX internal error return policy: Zero (OK) is
|
||||
* returned on success. A negated errno value is returned on failure:
|
||||
*
|
||||
* -ETIMEDOUT is returned on the timeout condition.
|
||||
* -ECANCELED may be returned if the thread is canceled while waiting.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -211,7 +201,7 @@ int nxsem_tickwait_uninterruptible(FAR sem_t *sem, clock_t start,
|
||||
|
||||
ret = nxsem_tickwait(sem, start, delay);
|
||||
}
|
||||
while (ret == -EINTR || ret == -ECANCELED);
|
||||
while (ret == -EINTR);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
@ -1,35 +1,20 @@
|
||||
/****************************************************************************
|
||||
* sched/semaphore/sem_timedwait.c
|
||||
*
|
||||
* Copyright (C) 2011, 2013-201, 2020 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -232,6 +217,7 @@ errout_with_irqdisabled:
|
||||
* ETIMEDOUT The semaphore could not be locked before the specified timeout
|
||||
* expired.
|
||||
* EDEADLK A deadlock condition was detected.
|
||||
* ECANCELED May be returned if the thread is canceled while waiting.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
@ -247,7 +233,7 @@ int nxsem_timedwait_uninterruptible(FAR sem_t *sem,
|
||||
|
||||
ret = nxsem_timedwait(sem, abstime);
|
||||
}
|
||||
while (ret == -EINTR || ret == -ECANCELED);
|
||||
while (ret == -EINTR);
|
||||
|
||||
return ret;
|
||||
}
|
||||
@ -285,6 +271,7 @@ int nxsem_timedwait_uninterruptible(FAR sem_t *sem,
|
||||
* expired.
|
||||
* EDEADLK A deadlock condition was detected.
|
||||
* EINTR A signal interrupted this function.
|
||||
* ECANCELED May be returned if the thread is canceled while waiting.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user