kernel: replace all usleep to nxsig_usleep in kernel space

syscall cannot be called from kernel space

Signed-off-by: chao an <anchao@xiaomi.com>
This commit is contained in:
chao an 2023-10-25 11:08:56 +08:00 committed by Xiang Xiao
parent ee84ea3875
commit 3cadf6642a
35 changed files with 81 additions and 48 deletions

View File

@ -2719,7 +2719,7 @@ static int cxd56_gnss_open(struct file *filep)
{
/* GNSS requires stable RTC */
usleep(100 * 1000);
nxsig_usleep(100 * 1000);
}
ret = nxmutex_lock(&priv->devlock);

View File

@ -29,6 +29,7 @@
#include <nuttx/nuttx.h>
#include <nuttx/kthread.h>
#include <nuttx/rptun/rptun.h>
#include <nuttx/signal.h>
#include <nuttx/semaphore.h>
@ -245,7 +246,7 @@ nrf53_rptun_get_resource(struct rptun_dev_s *dev)
while (priv->shmem->base == 0)
{
usleep(100);
nxsig_usleep(100);
}
}

View File

@ -27,6 +27,7 @@
#include <arch/irq.h>
#include <nuttx/mutex.h>
#include <nuttx/signal.h>
#include <nuttx/mm/mm.h>
@ -385,7 +386,7 @@ int nrf_modem_os_sleep(uint32_t timeout)
{
/* Timeout in ms */
usleep(timeout * 1000);
nxsig_usleep(timeout * 1000);
return OK;
}

View File

@ -38,6 +38,7 @@
#include <nuttx/arch.h>
#include <nuttx/net/usrsock.h>
#include <nuttx/net/ioctl.h>
#include <nuttx/signal.h>
#include <nuttx/wireless/lte/lte_ioctl.h>
#include <nuttx/wireless/lte/lte.h>
@ -682,7 +683,7 @@ static void nrf91_usrsock_poll_work(void *arg)
{
while (g_usrsock.sock[pollfd->fd].recvpending == true)
{
usleep(100);
nxsig_usleep(100);
}
}

View File

@ -29,6 +29,7 @@
#include <errno.h>
#include <nuttx/kmalloc.h>
#include <nuttx/signal.h>
#include <nuttx/wireless/ieee80211/bcmf_gspi.h>
#include "barriers.h"
@ -164,11 +165,11 @@ static int my_init(gspi_dev_t *gspi)
rp2040_gpio_setdir(rp_io->gpio_data, true);
rp2040_gpio_put(rp_io->gpio_data, false);
usleep(50000); /* Leave off for at least 50ms. */
nxsig_usleep(50000); /* Leave off for at least 50ms. */
rp2040_gpio_put(rp_io->gpio_on, true); /* power on */
usleep(50000); /* Wait a bit to let the power come up. */
nxsig_usleep(50000); /* Wait a bit to let the power come up. */
/* Don't let anyone else grab a PIO while we are doing so. */

View File

@ -30,6 +30,7 @@
#include <string.h>
#include <nuttx/kmalloc.h>
#include <nuttx/signal.h>
#include <nuttx/leds/ws2812.h>
#include <rp2040_pio.h>
@ -141,7 +142,7 @@ static void update_pixels(struct ws2812_dev_s *dev_data)
if (time_delta < 50)
{
usleep(50 - time_delta);
nxsig_usleep(50 - time_delta);
}
rp2040_dmastart(dma_handle, dma_complete, dev_data);

View File

@ -24,6 +24,7 @@
#include <nuttx/config.h>
#include <fcntl.h>
#include <nuttx/signal.h>
#include <nuttx/serial/serial.h>
#include <nuttx/net/netdev.h>
#include <nuttx/net/netdev/netdev.h>
@ -327,7 +328,7 @@ static int hci_load_firmware(struct file *filep)
command[1] = 0x20;
command[2] = 0xfc;
buffer_size = header_size + command[3];
usleep(10);
nxsig_usleep(10);
ret = hci_send(filep, command, buffer_size);
if (ret != buffer_size)
{

View File

@ -25,6 +25,7 @@
#include "amebaz_depend.h"
#include <nuttx/mqueue.h>
#include <nuttx/semaphore.h>
#include <nuttx/signal.h>
#include <nuttx/syslog/syslog.h>
/****************************************************************************
@ -397,7 +398,7 @@ void rtw_yield_os(void)
void rtw_usleep_os(int us)
{
usleep(us);
nxsig_usleep(us);
}
void rtw_msleep_os(int ms)

View File

@ -25,6 +25,7 @@
#include <nuttx/config.h>
#include <stdio.h>
#include <netinet/arp.h>
#include <nuttx/signal.h>
#include <nuttx/kmalloc.h>
#include "amebaz_netdev.h"
@ -958,7 +959,7 @@ int amebaz_wl_set_mode(struct amebaz_dev_s *priv, struct iwreq *iwr)
while (!rltk_wlan_running(priv->devnum))
{
usleep(1000);
nxsig_usleep(1000);
}
ret = amebaz_wl_disable_powersave(0);
@ -1125,7 +1126,7 @@ static int amebaz_wl_on(int mode)
while (!rltk_wlan_running(gp_wlan_dev[i]->devnum))
{
usleep(1000);
nxsig_usleep(1000);
}
}

View File

@ -38,6 +38,7 @@
#include <arch/board/board.h>
#include <nuttx/kmalloc.h>
#include <nuttx/mqueue.h>
#include <nuttx/signal.h>
#include <nuttx/fs/fs.h>
#include <nuttx/fs/ioctl.h>
#include <nuttx/audio/audio.h>
@ -665,7 +666,7 @@ void classd_enable_audio(struct classd_dev_s *priv, bool pmc_clock_enable)
/* wait for Audio PLL startup time */
usleep(100);
nxsig_usleep(100);
#endif
}

View File

@ -42,6 +42,7 @@
#include <nuttx/semaphore.h>
#include <nuttx/mmcsd.h>
#include <nuttx/kmalloc.h>
#include <nuttx/signal.h>
#include <nuttx/irq.h>
#include <arch/board/board.h>
@ -1578,7 +1579,7 @@ static void sam_reset(struct sdio_dev_s *dev)
}
timeout_ms--;
usleep(100);
nxsig_usleep(100);
}
mcinfo("Reset complete\n");
@ -1964,7 +1965,7 @@ static void sam_clock(struct sdio_dev_s *dev, enum sdio_clock_e rate)
if (wait_microseconds > 0)
{
usleep(wait_microseconds);
nxsig_usleep(wait_microseconds);
}
}
@ -2674,7 +2675,7 @@ static int sam_recvshortcrc(struct sdio_dev_s *dev, uint32_t cmd,
/* We need a short delay here to let the SDMMC peripheral respond */
usleep(10);
nxsig_usleep(10);
return ret;
}
@ -3323,7 +3324,7 @@ static int sam_set_clock(struct sam_dev_s *priv, uint32_t clock)
}
timeout--;
usleep(100);
nxsig_usleep(100);
}
sam_putreg16(priv, 0, SAMA5_SDMMC_SYSCTL_OFFSET);
@ -3433,7 +3434,7 @@ static int sam_set_clock(struct sam_dev_s *priv, uint32_t clock)
}
timeout--;
usleep(100);
nxsig_usleep(100);
}
/* High Speed Mode? */

View File

@ -41,6 +41,7 @@
#include <nuttx/arch.h>
#include <nuttx/fs/ioctl.h>
#include <nuttx/serial/serial.h>
#include <nuttx/signal.h>
#include <arch/board/board.h>
@ -1711,7 +1712,7 @@ static int sam_ioctl(struct file *filep, int cmd, unsigned long arg)
* waiting to improve CPU utilization
*/
usleep((8 * 1000 * 1000) / priv->baud);
nxsig_usleep((8 * 1000 * 1000) / priv->baud);
regval = sam_serialin(priv, SAM_UART_SR_OFFSET);
}

View File

@ -29,6 +29,7 @@
#include <nuttx/nuttx.h>
#include <nuttx/kthread.h>
#include <nuttx/rptun/rptun.h>
#include <nuttx/signal.h>
#include <nuttx/semaphore.h>
@ -250,7 +251,7 @@ stm32_rptun_get_resource(struct rptun_dev_s *dev)
while (priv->shmem->base == 0)
{
usleep(100);
nxsig_usleep(100);
}
}

View File

@ -2213,7 +2213,7 @@ int esp32c3_bt_controller_disable(void)
while (!btdm_power_state_active())
{
usleep(1000); /* wait */
nxsig_usleep(1000); /* wait */
}
btdm_controller_disable();

View File

@ -37,6 +37,7 @@
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/can/can.h>
#include <nuttx/signal.h>
#include "riscv_internal.h"
@ -1217,7 +1218,7 @@ struct can_dev_s *esp32c3_twaiinitialize(int port)
modifyreg32(SYSTEM_PERIP_RST_EN0_REG, 0, SYSTEM_TWAI_RST_M);
modifyreg32(SYSTEM_PERIP_CLK_EN0_REG, SYSTEM_TWAI_CLK_EN_M, 0);
usleep(1);
nxsig_usleep(1);
modifyreg32(SYSTEM_PERIP_CLK_EN0_REG, 0, SYSTEM_TWAI_CLK_EN_M);
modifyreg32(SYSTEM_PERIP_RST_EN0_REG, SYSTEM_TWAI_RST_M, 0);

View File

@ -25,6 +25,7 @@
#include <nuttx/config.h>
#include <errno.h>
#include <unistd.h>
#include <nuttx/signal.h>
#include "mpfs_dsn.h"
#include "riscv_internal.h"
@ -89,7 +90,7 @@ int mpfs_read_dsn(uint8_t *dsn, size_t len)
while ((getreg32(SERVICES_SR) & SCBCTRL_SERVICESSR_BUSY) && --retries > 0)
{
leave_critical_section(flags);
usleep(1000);
nxsig_usleep(1000);
flags = enter_critical_section();
}

View File

@ -2529,7 +2529,7 @@ int esp32_bt_controller_disable(void)
while (!btdm_power_state_active())
{
usleep(1000); /* wait */
nxsig_usleep(1000); /* wait */
}
btdm_controller_disable();

View File

@ -2658,7 +2658,7 @@ int esp32s3_bt_controller_disable(void)
while (!btdm_power_state_active())
{
usleep(1000); /* wait */
nxsig_usleep(1000); /* wait */
}
btdm_controller_disable();

View File

@ -25,6 +25,7 @@
#include <unistd.h>
#include <stdbool.h>
#include <string.h>
#include <nuttx/signal.h>
#include <arch/board/board.h>
#include "cxd56_gpio.h"
@ -116,9 +117,9 @@ int board_bluetooth_uart_pin_cfg(void)
void board_bluetooth_reset(void)
{
cxd56_gpio_write(BCM20707_RST_N, false);
usleep(BCM20707_RST_DELAY);
nxsig_usleep(BCM20707_RST_DELAY);
cxd56_gpio_write(BCM20707_RST_N, true);
usleep(BCM20707_RST_DELAY);
nxsig_usleep(BCM20707_RST_DELAY);
}
/****************************************************************************

View File

@ -33,6 +33,7 @@
#include <nuttx/arch.h>
#include <nuttx/mutex.h>
#include <nuttx/signal.h>
#include "chip.h"
#include "arm_internal.h"
@ -233,7 +234,7 @@ int board_power_control(int target, bool en)
if (!g_rtc_enabled && (PMIC_GET_TYPE(target) == PMIC_TYPE_GPO))
{
usleep(1);
nxsig_usleep(1);
}
}
@ -271,7 +272,7 @@ int board_power_control_tristate(int target, int value)
if (!g_rtc_enabled)
{
usleep(1);
nxsig_usleep(1);
}
}
else if (PMIC_GET_TYPE(target) == CHIP_TYPE_GPIO)

View File

@ -37,6 +37,7 @@
#include <nuttx/drivers/ramdisk.h>
#include <nuttx/fs/fs.h>
#include <nuttx/fs/nxffs.h>
#include <nuttx/signal.h>
#include "same70-qmtech.h"
@ -172,7 +173,7 @@ int sam_bringup(void)
{
if (sam_cardinserted(HSMCI0_SLOTNO))
{
usleep(1000 * 1000);
nxsig_usleep(1000 * 1000);
/* Mount the volume on HSMCI0 */

View File

@ -37,6 +37,7 @@
# include <nuttx/usb/usbmonitor.h>
#endif
#include <nuttx/signal.h>
#include <nuttx/drivers/drivers.h>
#include <nuttx/drivers/ramdisk.h>
#include <nuttx/fs/fs.h>
@ -233,7 +234,7 @@ int sam_bringup(void)
{
if (sam_cardinserted(HSMCI0_SLOTNO))
{
usleep(1000 * 1000);
nxsig_usleep(1000 * 1000);
/* Mount the volume on HSMCI0 */

View File

@ -32,6 +32,7 @@
#include <syslog.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/signal.h>
#ifdef CONFIG_USBMONITOR
# include <nuttx/usb/usbmonitor.h>
@ -349,7 +350,7 @@ int sam_bringup(void)
{
if (sam_cardinserted(HSMCI0_SLOTNO))
{
usleep(1000 * 1000);
nxsig_usleep(1000 * 1000);
/* Mount the volume on HSMCI0 */

View File

@ -31,6 +31,7 @@
#include <debug.h>
#include <nuttx/board.h>
#include <nuttx/signal.h>
#include <arch/board/board.h>
#ifdef CONFIG_SENSORS_HYT271
# include <nuttx/sensors/hyt271.h>
@ -110,7 +111,7 @@ static int stm32_i2c_power_reset(struct hyt271_bus_s *bus)
}
stm32_gpiowrite(BOARD_HYT271_POWOUT, false);
usleep(250000);
nxsig_usleep(250000);
stm32_gpiowrite(BOARD_HYT271_POWOUT, true);
while (1)

View File

@ -31,6 +31,7 @@
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <nuttx/signal.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/st7735.h>
@ -84,9 +85,9 @@ int board_lcd_initialize(void)
esp32s3_configgpio(GPIO_LCD_RST, OUTPUT);
esp32s3_gpiowrite(GPIO_LCD_RST, false);
usleep(10000);
nxsig_usleep(10000);
esp32s3_gpiowrite(GPIO_LCD_RST, true);
usleep(100000);
nxsig_usleep(100000);
return OK;
}

View File

@ -42,6 +42,7 @@
#include <nuttx/fs/ioctl.h>
#include <nuttx/audio/audio.h>
#include <nuttx/audio/audio_null.h>
#include <nuttx/signal.h>
/****************************************************************************
* Pre-processor Definitions
@ -171,7 +172,7 @@ static int null_sleep(FAR struct audio_lowerhalf_s *dev,
uint64_t sleep_time;
sleep_time = USEC_PER_SEC * (uint64_t)apb->nbytes / priv->scaler;
usleep(sleep_time);
nxsig_usleep(sleep_time);
#ifdef CONFIG_AUDIO_MULTI_SESSION
priv->dev.upper(priv->dev.priv, AUDIO_CALLBACK_DEQUEUE,
apb, OK, NULL);

View File

@ -26,11 +26,13 @@
#include <unistd.h>
#include <nuttx/signal.h>
/****************************************************************************
* Public Functions
****************************************************************************/
void sm_sleep(uint32_t msec)
{
usleep(1000 * msec);
nxsig_usleep(1000 * msec);
}

View File

@ -27,6 +27,7 @@
#include <nuttx/kmalloc.h>
#include <nuttx/kthread.h>
#include <nuttx/fs/fs.h>
#include <nuttx/signal.h>
#include <poll.h>
#include <errno.h>
#include <arch/board/board.h>
@ -1050,7 +1051,7 @@ static int altcom_recvthread(int argc, FAR char *argv[])
* does not accept any requests and must stay alive.
*/
sleep(1);
nxsig_sleep(1);
}
}
else if (ret == ALTMDM_RETURN_EXIT)

View File

@ -28,6 +28,8 @@
#include <errno.h>
#include <debug.h>
#include <nuttx/signal.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@ -137,7 +139,7 @@ static int a4988_work(FAR struct stepper_lowerhalf_s *dev,
if (priv->auto_idle)
{
priv->ops->idle(false);
usleep(USEC_PER_MSEC);
nxsig_usleep(USEC_PER_MSEC);
}
dev->status.state = STEPPER_STATE_RUN;
@ -197,7 +199,7 @@ static int a4988_idle(FAR struct stepper_lowerhalf_s *dev, uint8_t idle)
else
{
priv->ops->idle(false);
usleep(USEC_PER_MSEC);
nxsig_usleep(USEC_PER_MSEC);
dev->status.state = STEPPER_STATE_READY;
}

View File

@ -27,6 +27,7 @@
#include <errno.h>
#include <debug.h>
#include <nuttx/signal.h>
/****************************************************************************
* Pre-processor Definitions
@ -144,7 +145,7 @@ static int drv8825_work(FAR struct stepper_lowerhalf_s *dev,
if (priv->auto_idle)
{
priv->ops->idle(false);
usleep(USEC_PER_MSEC * 2);
nxsig_usleep(USEC_PER_MSEC * 2);
}
dev->status.state = STEPPER_STATE_RUN;
@ -222,7 +223,7 @@ static int drv8825_idle(FAR struct stepper_lowerhalf_s *dev, uint8_t idle)
else
{
priv->ops->idle(false);
usleep(USEC_PER_MSEC * 2);
nxsig_usleep(USEC_PER_MSEC * 2);
dev->status.state = STEPPER_STATE_READY;
}

View File

@ -29,6 +29,7 @@
#include <string.h>
#include <sys/param.h>
#include <time.h>
#include <nuttx/signal.h>
#include "rptun.h"
@ -167,7 +168,7 @@ int rptun_ping(FAR struct rpmsg_endpoint *ept,
max = MAX(max, tm);
total += tm;
usleep(ping->sleep * USEC_PER_MSEC);
nxsig_usleep(ping->sleep * USEC_PER_MSEC);
}
syslog(LOG_INFO, "ping times: %d\n", ping->times);

View File

@ -25,6 +25,7 @@
#include "bmi160_base.h"
#include <sys/param.h>
#include <nuttx/wqueue.h>
#include <nuttx/signal.h>
#include <nuttx/sensors/sensor.h>
#if defined(CONFIG_SENSORS_BMI160_UORB)
@ -206,7 +207,7 @@ static void bmi160_accel_enable(FAR struct bmi160_dev_uorb_s *priv,
/* Set accel as normal mode. */
bmi160_putreg8(&priv->dev, BMI160_CMD, ACCEL_PM_NORMAL);
usleep(30000);
nxsig_usleep(30000);
idx = bmi160_findodr(priv->interval, g_bmi160_accel_odr,
nitems(g_bmi160_accel_odr));
@ -257,7 +258,7 @@ static void bmi160_gyro_enable(FAR struct bmi160_dev_uorb_s *priv,
/* Set gyro as normal mode. */
bmi160_putreg8(&priv->dev, BMI160_CMD, GYRO_PM_NORMAL);
usleep(30000);
nxsig_usleep(30000);
idx = bmi160_findodr(priv->interval, g_bmi160_gyro_odr,
nitems(g_bmi160_gyro_odr));
@ -594,7 +595,7 @@ static int bmi160_register_accel(int devno,
bmi160_getreg8(priv, 0x7f);
bmi160_getreg8(priv, 0x7f); /* workaround: fail to switch SPI, run twice */
usleep(200);
nxsig_usleep(200);
#endif

View File

@ -29,6 +29,7 @@
#include <nuttx/sensors/wtgahrs2.h>
#include <nuttx/kthread.h>
#include <nuttx/kmalloc.h>
#include <nuttx/signal.h>
#include <sys/param.h>
@ -151,7 +152,7 @@ static void wtgahrs2_sendcmd(FAR struct wtgahrs2_dev_s *rtdata,
const void *cmd)
{
file_write(&rtdata->file, cmd, WTGAHRS2_CMD_LENGTH);
usleep(10000);
nxsig_usleep(10000);
}
static int wtgahrs2_activate(FAR struct sensor_lowerhalf_s *lower,

View File

@ -35,6 +35,7 @@
#include <nuttx/mutex.h>
#include <nuttx/wqueue.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/signal.h>
#include <nuttx/usb/fusb302.h>
#include <sys/ioctl.h>
@ -644,7 +645,7 @@ void setmdac(struct fusb302_dev_s *priv, enum src_current_e thresh)
regval |= MEASURE_MDAC(src_mdac_val[thresh]);
fusb302_putreg(priv, FUSB302_MEASURE_REG, regval);
usleep(150);
nxsig_usleep(150);
}
/****************************************************************************

View File

@ -40,6 +40,7 @@
#include <nuttx/mutex.h>
#include <nuttx/fs/fs.h>
#include <nuttx/fs/ioctl.h>
#include <nuttx/signal.h>
#include "rpmsgfs.h"
@ -260,7 +261,7 @@ static void rpmsgfs_mkpath(FAR struct rpmsgfs_mountpt_s *fs,
break;
}
usleep(RPMSGFS_RETRY_DELAY_MS * USEC_PER_MSEC);
nxsig_usleep(RPMSGFS_RETRY_DELAY_MS * USEC_PER_MSEC);
fs->timeout -= RPMSGFS_RETRY_DELAY_MS;
}
}