From 0334b280cb34deda6ed01ef06783d3f5eecdefa6 Mon Sep 17 00:00:00 2001 From: Peter Bigot Date: Sun, 6 Oct 2019 13:56:20 -0500 Subject: [PATCH 1/6] scripts/coccinelle: more cleanup of int literal to timeout Sort the functions within the regular expression so they can be checked more easily. Remove k_thread_deadline_set as it takes an argument in cycles. (The one in-tree call to this function was not affected by this error.) Add missed k_mbox_data_block_get. Fix an overly ambitious multi-match disjunct that covered some non-existent functions. Signed-off-by: Peter Bigot --- .../coccinelle/int_literal_to_timeout.cocci | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/scripts/coccinelle/int_literal_to_timeout.cocci b/scripts/coccinelle/int_literal_to_timeout.cocci index 99f0b31f85cd3..6d53aedf73ac6 100644 --- a/scripts/coccinelle/int_literal_to_timeout.cocci +++ b/scripts/coccinelle/int_literal_to_timeout.cocci @@ -18,18 +18,19 @@ virtual report // Base rule provides the complex identifier regular expression @r_last_timeout@ identifier last_timeout =~ "(?x)^k_ -( timer_start -| queue_get +( delayed_work_submit(|_to_queue) | futex_wait -| stack_pop -| delayed_work_submit(|_to_queue) -| work_poll_submit(|_to_queue) +| mbox_data_block_get +| (mbox|msgq)_get +| mem_(pool|slab)_alloc | mutex_lock -| sem_take -| (msgq|mbox|pipe)_(block_)?(put|get) -| mem_(slab|pool)_alloc +| pipe_(get|put) | poll -| thread_deadline_set +| queue_get +| sem_take +| stack_pop +| timer_start +| work_poll_submit(|_to_queue) )$"; @@ last_timeout(...) From aa19c996c2d892dc549f4a26c488182f638e5f29 Mon Sep 17 00:00:00 2001 From: Peter Bigot Date: Sun, 6 Oct 2019 13:56:20 -0500 Subject: [PATCH 2/6] coccinelle: standardize k_mbox_data_block_get call with timeout Re-run with updated script to convert integer literal delay arguments to k_mbox_data_block_get to use the standard timeout macros. Signed-off-by: Peter Bigot --- tests/kernel/mbox/mbox_api/src/test_mbox_api.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/tests/kernel/mbox/mbox_api/src/test_mbox_api.c b/tests/kernel/mbox/mbox_api/src/test_mbox_api.c index 7f9cc2e0a214a..d7224b9284862 100644 --- a/tests/kernel/mbox/mbox_api/src/test_mbox_api.c +++ b/tests/kernel/mbox/mbox_api/src/test_mbox_api.c @@ -419,7 +419,8 @@ static void tmbox_get(struct k_mbox *pmbox) NULL); zassert_true(k_mbox_data_block_get - (&mmsg, &mpoolrx, &rxblock, 1) == -EAGAIN, NULL); + (&mmsg, &mpoolrx, &rxblock, K_MSEC(1)) == -EAGAIN, + NULL); /* Now dispose of the block since the test case finished */ k_mbox_data_get(&mmsg, NULL); From d7cccb2742e887f7adbeed49d085c48aadee1943 Mon Sep 17 00:00:00 2001 From: Peter Bigot Date: Sun, 6 Oct 2019 14:01:08 -0500 Subject: [PATCH 3/6] scripts/coccinelle: add sleep to int literal to timeout standardization k_sleep uses the same underlying thread infrastructure as the other functions that take timeouts, so the delay should be specified as a timeout rather than milliseconds. Signed-off-by: Peter Bigot --- scripts/coccinelle/int_literal_to_timeout.cocci | 1 + 1 file changed, 1 insertion(+) diff --git a/scripts/coccinelle/int_literal_to_timeout.cocci b/scripts/coccinelle/int_literal_to_timeout.cocci index 6d53aedf73ac6..e0ab0748bbfef 100644 --- a/scripts/coccinelle/int_literal_to_timeout.cocci +++ b/scripts/coccinelle/int_literal_to_timeout.cocci @@ -28,6 +28,7 @@ identifier last_timeout =~ "(?x)^k_ | poll | queue_get | sem_take +| sleep | stack_pop | timer_start | work_poll_submit(|_to_queue) From 5d359e92e19eecfec0ff7adcb912d6d48c13f742 Mon Sep 17 00:00:00 2001 From: Peter Bigot Date: Sun, 6 Oct 2019 14:02:31 -0500 Subject: [PATCH 4/6] coccinelle: standardize k_sleep calls with integer timeouts Re-run with updated script to convert integer literal delay arguments to k_sleep to use the standard timeout macros. Signed-off-by: Peter Bigot --- boards/arm/nrf52_pca20020/board.c | 2 +- boards/arm/nrf9160_pca10090/nrf52840_reset.c | 2 +- drivers/bluetooth/hci/h5.c | 4 ++-- drivers/bluetooth/hci/spi.c | 2 +- drivers/display/display_ili9340.c | 8 ++++---- drivers/display/display_ili9340_seeed_tftv2.c | 4 ++-- drivers/display/display_st7789v.c | 10 +++++----- drivers/ethernet/eth_enc424j600.c | 6 +++--- drivers/ethernet/eth_smsc911x.c | 8 ++++---- drivers/ethernet/eth_stm32_hal.c | 2 +- drivers/ethernet/phy_sam_gmac.c | 6 +++--- drivers/i2s/i2s_ll_stm32.c | 2 +- drivers/led/lp5562.c | 2 +- drivers/pwm/pwm_imx.c | 2 +- drivers/sensor/adxl362/adxl362.c | 2 +- drivers/sensor/adxl372/adxl372.c | 2 +- drivers/sensor/ams_iAQcore/iAQcore.c | 2 +- drivers/sensor/apds9960/apds9960.c | 2 +- drivers/sensor/ccs811/ccs811.c | 6 +++--- drivers/sensor/ens210/ens210.c | 4 ++-- drivers/sensor/hts221/hts221.c | 2 +- drivers/sensor/lsm6dsl/lsm6dsl_shub.c | 6 +++--- drivers/sensor/lsm6dso/lsm6dso_shub.c | 6 +++--- drivers/sensor/vl53l0x/vl53l0x.c | 2 +- drivers/sensor/vl53l0x/vl53l0x_platform.c | 2 +- drivers/usb/device/usb_dc_native_posix_adapt.c | 6 +++--- drivers/wifi/eswifi/eswifi_bus_spi.c | 4 ++-- drivers/wifi/eswifi/eswifi_core.c | 4 ++-- samples/boards/96b_argonkey/sensors/src/main.c | 4 ++-- samples/boards/sensortile_box/src/main.c | 4 ++-- samples/display/cfb/src/main.c | 2 +- samples/display/ili9340/src/main.c | 2 +- samples/display/st7789v/src/main.c | 2 +- samples/drivers/entropy/src/main.c | 2 +- samples/drivers/espi/src/main.c | 2 +- samples/drivers/ht16k33/src/main.c | 4 ++-- samples/drivers/lcd_hd44780/src/main.c | 18 +++++++++--------- samples/drivers/ps2/src/main.c | 2 +- samples/drivers/watchdog/src/main.c | 2 +- samples/gui/lvgl/src/main.c | 2 +- samples/net/mqtt_publisher/src/main.c | 2 +- samples/philosophers/src/main.c | 2 +- .../cmsis_rtos_v2/philosophers/src/main.c | 2 +- samples/sensor/adt7420/src/main.c | 2 +- samples/sensor/adxl362/src/main.c | 2 +- samples/sensor/adxl372/src/main.c | 2 +- samples/sensor/amg88xx/src/main.c | 2 +- samples/sensor/ams_iAQcore/src/main.c | 2 +- samples/sensor/apds9960/src/main.c | 4 ++-- samples/sensor/bme280/src/main.c | 2 +- samples/sensor/bme680/src/main.c | 2 +- samples/sensor/bmm150/src/main.c | 2 +- samples/sensor/ccs811/src/main.c | 2 +- samples/sensor/ens210/src/main.c | 2 +- samples/sensor/hts221/src/main.c | 2 +- samples/sensor/lsm303dlhc/src/main.c | 2 +- samples/sensor/lsm6dsl/src/main.c | 2 +- samples/sensor/magn_polling/src/main.c | 2 +- samples/sensor/max30101/src/main.c | 2 +- samples/sensor/max44009/src/main.c | 2 +- samples/sensor/mcp9808/src/main.c | 2 +- samples/sensor/ms5837/src/main.c | 2 +- samples/sensor/sht3xd/src/main.c | 2 +- samples/sensor/sx9500/src/main.c | 4 ++-- samples/sensor/th02/src/main.c | 2 +- samples/sensor/thermometer/src/main.c | 2 +- samples/sensor/tmp112/src/main.c | 2 +- samples/sensor/tmp116/src/main.c | 2 +- samples/sensor/vl53l0x/src/main.c | 2 +- samples/shields/x_nucleo_iks01a1/src/main.c | 2 +- samples/shields/x_nucleo_iks01a2/src/main.c | 2 +- .../x_nucleo_iks01a3/sensorhub/src/main.c | 2 +- .../x_nucleo_iks01a3/standard/src/main.c | 2 +- samples/subsys/fs/fat_fs/src/main.c | 2 +- samples/subsys/logging/logger/src/main.c | 4 ++-- samples/subsys/mgmt/mcumgr/smp_svr/src/main.c | 2 +- samples/subsys/usb/cdc_acm/src/main.c | 2 +- .../subsys/usb/cdc_acm_composite/src/main.c | 4 ++-- samples/userspace/shared_mem/src/main.c | 6 +++--- subsys/console/tty.c | 2 +- subsys/testsuite/include/timestamp.h | 2 +- .../arm/arm_runtime_nmi/src/arm_runtime_nmi.c | 2 +- tests/benchmarks/boot_time/src/main.c | 2 +- tests/benchmarks/sched/src/main.c | 2 +- tests/benchmarks/sys_kernel/src/syskernel.c | 2 +- .../timing_info/src/msg_passing_bench.c | 8 ++++---- .../timing_info/src/semaphore_bench.c | 4 ++-- .../benchmarks/timing_info/src/thread_bench.c | 4 ++-- tests/benchmarks/timing_info/src/yield_bench.c | 4 ++-- .../bsim_bt/bsim_test_app/src/test_connect1.c | 2 +- .../bsim_bt/bsim_test_app/src/test_empty.c | 2 +- .../native_posix/native_tasks/src/main.c | 2 +- .../clock_control_api/src/test_clock_control.c | 2 +- .../counter_basic_api/src/test_counter.c | 2 +- .../dma/chan_blen_transfer/src/test_dma.c | 2 +- .../gpio_basic_api/src/test_callback_manage.c | 8 ++++---- .../gpio_basic_api/src/test_callback_trigger.c | 4 ++-- .../gpio/gpio_basic_api/src/test_pin_rw.c | 2 +- tests/drivers/i2c/i2c_api/src/test_i2c.c | 4 ++-- .../i2s/i2s_api/src/test_i2s_loopback.c | 8 ++++---- .../drivers/i2s/i2s_api/src/test_i2s_states.c | 2 +- .../pinmux/pinmux_basic_api/src/pinmux_gpio.c | 2 +- tests/drivers/pwm/pwm_api/src/test_pwm.c | 16 ++++++++-------- .../uart/uart_basic_api/src/test_uart_fifo.c | 2 +- .../watchdog/wdt_basic_api/src/test_wdt.c | 2 +- .../fifo/fifo_api/src/test_fifo_cancel.c | 2 +- tests/kernel/fifo/fifo_timeout/src/main.c | 6 +++--- tests/kernel/fp_sharing/generic/src/main.c | 4 ++-- tests/kernel/fp_sharing/generic/src/pi.c | 2 +- .../src/test_mpool_alloc_wait.c | 2 +- tests/kernel/mem_protect/userspace/src/main.c | 16 ++++++++-------- .../mslab_concept/src/test_mslab_alloc_wait.c | 2 +- tests/kernel/mutex/sys_mutex/src/main.c | 2 +- .../pipe/pipe_api/src/test_pipe_contexts.c | 6 +++--- tests/kernel/poll/src/test_poll.c | 10 +++++----- tests/kernel/queue/src/test_queue_contexts.c | 2 +- tests/kernel/sched/deadline/src/main.c | 4 ++-- tests/kernel/sched/preempt/src/main.c | 2 +- .../src/test_priority_scheduling.c | 2 +- .../schedule_api/src/test_sched_priority.c | 4 ++-- .../src/test_sched_timeslice_and_lock.c | 4 ++-- tests/kernel/smp/src/main.c | 4 ++-- tests/kernel/threads/thread_apis/src/main.c | 8 ++++---- .../thread_apis/src/test_kthread_for_each.c | 2 +- .../src/test_threads_cancel_abort.c | 16 ++++++++-------- .../thread_apis/src/test_threads_spawn.c | 8 ++++---- .../src/test_threads_suspend_resume.c | 4 ++-- tests/kernel/tickless/tickless/src/main.c | 2 +- tests/kernel/timer/timer_monotonic/src/main.c | 2 +- .../fcb_init/src/settings_test_fcb_init.c | 2 +- 130 files changed, 229 insertions(+), 229 deletions(-) diff --git a/boards/arm/nrf52_pca20020/board.c b/boards/arm/nrf52_pca20020/board.c index 4de76762c5048..b23707de46662 100644 --- a/boards/arm/nrf52_pca20020/board.c +++ b/boards/arm/nrf52_pca20020/board.c @@ -30,7 +30,7 @@ static int pwr_ctrl_init(struct device *dev) gpio_pin_configure(gpio, cfg->pin, GPIO_DIR_OUT); gpio_pin_write(gpio, cfg->pin, 1); - k_sleep(1); /* Wait for the rail to come up and stabilize */ + k_sleep(K_MSEC(1)); /* Wait for the rail to come up and stabilize */ return 0; } diff --git a/boards/arm/nrf9160_pca10090/nrf52840_reset.c b/boards/arm/nrf9160_pca10090/nrf52840_reset.c index dd7ded9f0e64b..cf96e92b1d4a4 100644 --- a/boards/arm/nrf9160_pca10090/nrf52840_reset.c +++ b/boards/arm/nrf9160_pca10090/nrf52840_reset.c @@ -55,7 +55,7 @@ int bt_hci_transport_setup(struct device *h4) * It is critical (!) to wait here, so that all bytes * on the lines are received and drained correctly. */ - k_sleep(1); + k_sleep(K_MSEC(1)); /* Drain bytes */ while (uart_fifo_read(h4, &c, 1)) { diff --git a/drivers/bluetooth/hci/h5.c b/drivers/bluetooth/hci/h5.c index 3633ef5b385b3..cf35f8cb50a50 100644 --- a/drivers/bluetooth/hci/h5.c +++ b/drivers/bluetooth/hci/h5.c @@ -608,11 +608,11 @@ static void tx_thread(void) switch (h5.link_state) { case UNINIT: /* FIXME: send sync */ - k_sleep(100); + k_sleep(K_MSEC(100)); break; case INIT: /* FIXME: send conf */ - k_sleep(100); + k_sleep(K_MSEC(100)); break; case ACTIVE: buf = net_buf_get(&h5.tx_queue, K_FOREVER); diff --git a/drivers/bluetooth/hci/spi.c b/drivers/bluetooth/hci/spi.c index e92dc890b1091..bc00ab445a944 100644 --- a/drivers/bluetooth/hci/spi.c +++ b/drivers/bluetooth/hci/spi.c @@ -407,7 +407,7 @@ static int bt_spi_send(struct net_buf *buf) if (!pending) { break; } - k_sleep(1); + k_sleep(K_MSEC(1)); } k_sem_take(&sem_busy, K_FOREVER); diff --git a/drivers/display/display_ili9340.c b/drivers/display/display_ili9340.c index 973f8eca1ff28..911ba48139ed7 100644 --- a/drivers/display/display_ili9340.c +++ b/drivers/display/display_ili9340.c @@ -42,7 +42,7 @@ struct ili9340_data { static void ili9340_exit_sleep(struct ili9340_data *data) { ili9340_transmit(data, ILI9340_CMD_EXIT_SLEEP, NULL, 0); - k_sleep(120); + k_sleep(K_MSEC(120)); } static int ili9340_init(struct device *dev) @@ -96,11 +96,11 @@ static int ili9340_init(struct device *dev) #ifdef DT_INST_0_ILITEK_ILI9340_RESET_GPIOS_CONTROLLER LOG_DBG("Resetting display driver"); gpio_pin_write(data->reset_gpio, DT_INST_0_ILITEK_ILI9340_RESET_GPIOS_PIN, 1); - k_sleep(1); + k_sleep(K_MSEC(1)); gpio_pin_write(data->reset_gpio, DT_INST_0_ILITEK_ILI9340_RESET_GPIOS_PIN, 0); - k_sleep(1); + k_sleep(K_MSEC(1)); gpio_pin_write(data->reset_gpio, DT_INST_0_ILITEK_ILI9340_RESET_GPIOS_PIN, 1); - k_sleep(5); + k_sleep(K_MSEC(5)); #endif LOG_DBG("Initializing LCD"); diff --git a/drivers/display/display_ili9340_seeed_tftv2.c b/drivers/display/display_ili9340_seeed_tftv2.c index 329e5646ce40d..1312b32d42e8e 100644 --- a/drivers/display/display_ili9340_seeed_tftv2.c +++ b/drivers/display/display_ili9340_seeed_tftv2.c @@ -22,7 +22,7 @@ void ili9340_lcd_init(struct ili9340_data *p_ili9340) cmd = ILI9340_CMD_SOFTWARE_RESET; ili9340_transmit(p_ili9340, cmd, NULL, 0); - k_sleep(5); + k_sleep(K_MSEC(5)); cmd = ILI9341_CMD_POWER_CTRL_B; data[0] = 0x00U; @@ -166,7 +166,7 @@ void ili9340_lcd_init(struct ili9340_data *p_ili9340) cmd = ILI9340_CMD_EXIT_SLEEP; ili9340_transmit(p_ili9340, cmd, NULL, 0); - k_sleep(120); + k_sleep(K_MSEC(120)); /* Display Off */ cmd = ILI9340_CMD_DISPLAY_OFF; diff --git a/drivers/display/display_st7789v.c b/drivers/display/display_st7789v.c index c652a6139352d..c3254387335f7 100644 --- a/drivers/display/display_st7789v.c +++ b/drivers/display/display_st7789v.c @@ -81,7 +81,7 @@ void st7789v_transmit(struct st7789v_data *data, u8_t cmd, static void st7789v_exit_sleep(struct st7789v_data *data) { st7789v_transmit(data, ST7789V_CMD_SLEEP_OUT, NULL, 0); - k_sleep(120); + k_sleep(K_MSEC(120)); } static void st7789v_reset_display(struct st7789v_data *data) @@ -89,14 +89,14 @@ static void st7789v_reset_display(struct st7789v_data *data) LOG_DBG("Resetting display"); #ifdef DT_INST_0_SITRONIX_ST7789V_RESET_GPIOS_CONTROLLER gpio_pin_write(data->reset_gpio, ST7789V_RESET_PIN, 1); - k_sleep(1); + k_sleep(K_MSEC(1)); gpio_pin_write(data->reset_gpio, ST7789V_RESET_PIN, 0); - k_sleep(6); + k_sleep(K_MSEC(6)); gpio_pin_write(data->reset_gpio, ST7789V_RESET_PIN, 1); - k_sleep(20); + k_sleep(K_MSEC(20)); #else st7789v_transmit(p_st7789v, ST7789V_CMD_SW_RESET, NULL, 0); - k_sleep(5); + k_sleep(K_MSEC(5)); #endif } diff --git a/drivers/ethernet/eth_enc424j600.c b/drivers/ethernet/eth_enc424j600.c index baf21d2fd0df9..3e9a5329abfa4 100644 --- a/drivers/ethernet/eth_enc424j600.c +++ b/drivers/ethernet/eth_enc424j600.c @@ -325,7 +325,7 @@ static int enc424j600_tx(struct device *dev, struct net_pkt *pkt) enc424j600_write_sbc(dev, ENC424J600_1BC_SETTXRTS); do { - k_sleep(1); + k_sleep(K_MSEC(1)); enc424j600_read_sfru(dev, ENC424J600_SFRX_ECON1L, &tmp); } while (tmp & ENC424J600_ECON1_TXRTS); @@ -545,12 +545,12 @@ static int enc424j600_stop_device(struct device *dev) ENC424J600_ECON1_RXEN); do { - k_sleep(10U); + k_sleep(K_MSEC(10U)); enc424j600_read_sfru(dev, ENC424J600_SFRX_ESTATL, &tmp); } while (tmp & ENC424J600_ESTAT_RXBUSY); do { - k_sleep(10U); + k_sleep(K_MSEC(10U)); enc424j600_read_sfru(dev, ENC424J600_SFRX_ECON1L, &tmp); } while (tmp & ENC424J600_ECON1_TXRTS); diff --git a/drivers/ethernet/eth_smsc911x.c b/drivers/ethernet/eth_smsc911x.c index 2c96861652901..209cee19a14ec 100644 --- a/drivers/ethernet/eth_smsc911x.c +++ b/drivers/ethernet/eth_smsc911x.c @@ -106,7 +106,7 @@ int smsc_phy_regread(u8_t regoffset, u32_t *data) val = 0U; do { - k_sleep(1); + k_sleep(K_MSEC(1)); time_out--; if (smsc_mac_regread(SMSC9220_MAC_MII_ACC, &val)) { return -1; @@ -152,7 +152,7 @@ int smsc_phy_regwrite(u8_t regoffset, u32_t data) } do { - k_sleep(1); + k_sleep(K_MSEC(1)); time_out--; if (smsc_mac_regread(SMSC9220_MAC_MII_ACC, &phycmd)) { return -1; @@ -222,7 +222,7 @@ static int smsc_soft_reset(void) SMSC9220->HW_CFG |= HW_CFG_SRST; do { - k_sleep(1); + k_sleep(K_MSEC(1)); time_out--; } while (time_out != 0U && (SMSC9220->HW_CFG & HW_CFG_SRST)); @@ -402,7 +402,7 @@ int smsc_init(void) SMSC9220->FIFO_INT &= ~(0xFF); /* Clear 2 bottom nibbles */ /* This sleep is compulsory otherwise txmit/receive will fail. */ - k_sleep(2000); + k_sleep(K_MSEC(2000)); return 0; } diff --git a/drivers/ethernet/eth_stm32_hal.c b/drivers/ethernet/eth_stm32_hal.c index 5f40a7508ebf2..2d53673ced0f2 100644 --- a/drivers/ethernet/eth_stm32_hal.c +++ b/drivers/ethernet/eth_stm32_hal.c @@ -87,7 +87,7 @@ static inline void disable_mcast_filter(ETH_HandleTypeDef *heth) * at least four TX_CLK/RX_CLK clock cycles */ tmp = heth->Instance->MACFFR; - k_sleep(1); + k_sleep(K_MSEC(1)); heth->Instance->MACFFR = tmp; } diff --git a/drivers/ethernet/phy_sam_gmac.c b/drivers/ethernet/phy_sam_gmac.c index 3c36478c6bd6a..7aa23ad511aca 100644 --- a/drivers/ethernet/phy_sam_gmac.c +++ b/drivers/ethernet/phy_sam_gmac.c @@ -47,7 +47,7 @@ static int mdio_bus_wait(Gmac *gmac) return -ETIMEDOUT; } - k_sleep(10); + k_sleep(K_MSEC(10)); } return 0; @@ -127,7 +127,7 @@ static int phy_soft_reset(const struct phy_sam_gmac_dev *phy) return -ETIMEDOUT; } - k_sleep(50); + k_sleep(K_MSEC(50)); retval = phy_read(phy, MII_BMCR, &phy_reg); if (retval < 0) { @@ -228,7 +228,7 @@ int phy_sam_gmac_auto_negotiate(const struct phy_sam_gmac_dev *phy, goto auto_negotiate_exit; } - k_sleep(100); + k_sleep(K_MSEC(100)); retval = phy_read(phy, MII_BMSR, &val); if (retval < 0) { diff --git a/drivers/i2s/i2s_ll_stm32.c b/drivers/i2s/i2s_ll_stm32.c index 43be4e340b9cd..76c8b40bb4b4f 100644 --- a/drivers/i2s/i2s_ll_stm32.c +++ b/drivers/i2s/i2s_ll_stm32.c @@ -140,7 +140,7 @@ static int i2s_stm32_set_clock(struct device *dev, u32_t bit_clk_freq) } /* wait 1 ms */ - k_sleep(1); + k_sleep(K_MSEC(1)); } LOG_DBG("PLLI2S is locked"); diff --git a/drivers/led/lp5562.c b/drivers/led/lp5562.c index 650e8c9a9fef0..483b668c48e87 100644 --- a/drivers/led/lp5562.c +++ b/drivers/led/lp5562.c @@ -489,7 +489,7 @@ static inline int lp5562_set_engine_exec_state(struct device *dev, * Delay between consecutive I2C writes to * ENABLE register (00h) need to be longer than 488μs (typ.). */ - k_sleep(1); + k_sleep(K_MSEC(1)); return ret; } diff --git a/drivers/pwm/pwm_imx.c b/drivers/pwm/pwm_imx.c index 10b88fcfafcbe..af8d793f097d9 100644 --- a/drivers/pwm/pwm_imx.c +++ b/drivers/pwm/pwm_imx.c @@ -96,7 +96,7 @@ static int imx_pwm_pin_set(struct device *dev, u32_t pwm, } else { PWM_PWMCR_REG(base) = PWM_PWMCR_SWR(1); do { - k_sleep(1); + k_sleep(K_MSEC(1)); cr = PWM_PWMCR_REG(base); } while ((PWM_PWMCR_SWR(cr)) && (++wait_count < CONFIG_PWM_PWMSWR_LOOP)); diff --git a/drivers/sensor/adxl362/adxl362.c b/drivers/sensor/adxl362/adxl362.c index dd561bcb08e77..6d335d4797771 100644 --- a/drivers/sensor/adxl362/adxl362.c +++ b/drivers/sensor/adxl362/adxl362.c @@ -755,7 +755,7 @@ static int adxl362_init(struct device *dev) return -ENODEV; } - k_sleep(5); + k_sleep(K_MSEC(5)); adxl362_get_reg(dev, &value, ADXL362_REG_PARTID, 1); if (value != ADXL362_PART_ID) { diff --git a/drivers/sensor/adxl372/adxl372.c b/drivers/sensor/adxl372/adxl372.c index 171c26f8cbda3..ad0048d35b8fb 100644 --- a/drivers/sensor/adxl372/adxl372.c +++ b/drivers/sensor/adxl372/adxl372.c @@ -502,7 +502,7 @@ static int adxl372_reset(struct device *dev) } /* Writing code 0x52 resets the device */ ret = adxl372_reg_write(dev, ADXL372_RESET, ADXL372_RESET_CODE); - k_sleep(1000); + k_sleep(K_MSEC(1000)); return ret; } diff --git a/drivers/sensor/ams_iAQcore/iAQcore.c b/drivers/sensor/ams_iAQcore/iAQcore.c index 07036ecc420c1..9b9833beaffae 100644 --- a/drivers/sensor/ams_iAQcore/iAQcore.c +++ b/drivers/sensor/ams_iAQcore/iAQcore.c @@ -51,7 +51,7 @@ static int iaqcore_sample_fetch(struct device *dev, enum sensor_channel chan) return 0; } - k_sleep(100); + k_sleep(K_MSEC(100)); } if (drv_data->status == 0x01) { diff --git a/drivers/sensor/apds9960/apds9960.c b/drivers/sensor/apds9960/apds9960.c index ef99413c237dd..e998906301dd2 100644 --- a/drivers/sensor/apds9960/apds9960.c +++ b/drivers/sensor/apds9960/apds9960.c @@ -447,7 +447,7 @@ static int apds9960_init(struct device *dev) struct apds9960_data *data = dev->driver_data; /* Initialize time 5.7ms */ - k_sleep(6); + k_sleep(K_MSEC(6)); data->i2c = device_get_binding(config->i2c_name); if (data->i2c == NULL) { diff --git a/drivers/sensor/ccs811/ccs811.c b/drivers/sensor/ccs811/ccs811.c index 14770a3ffdaac..e4591ed7f3e27 100644 --- a/drivers/sensor/ccs811/ccs811.c +++ b/drivers/sensor/ccs811/ccs811.c @@ -38,7 +38,7 @@ static int ccs811_sample_fetch(struct device *dev, enum sensor_channel chan) break; } - k_sleep(100); + k_sleep(K_MSEC(100)); } if (!(status & CCS811_STATUS_DATA_READY)) { @@ -180,7 +180,7 @@ int ccs811_init(struct device *dev) GPIO_DIR_OUT); gpio_pin_write(drv_data->gpio, CONFIG_CCS811_GPIO_RESET_PIN_NUM, 1); - k_sleep(1); + k_sleep(K_MSEC(1)); #endif /* @@ -192,7 +192,7 @@ int ccs811_init(struct device *dev) GPIO_DIR_OUT); gpio_pin_write(drv_data->gpio, CONFIG_CCS811_GPIO_WAKEUP_PIN_NUM, 0); - k_sleep(1); + k_sleep(K_MSEC(1)); #endif /* Switch device to application mode */ diff --git a/drivers/sensor/ens210/ens210.c b/drivers/sensor/ens210/ens210.c index 656f1c35ec609..f1679099d172e 100644 --- a/drivers/sensor/ens210/ens210.c +++ b/drivers/sensor/ens210/ens210.c @@ -162,7 +162,7 @@ static int ens210_wait_boot(struct device *i2c_dev) (u8_t *)&sys_stat); if (ret < 0) { - k_sleep(1); + k_sleep(K_MSEC(1)); continue; } @@ -176,7 +176,7 @@ static int ens210_wait_boot(struct device *i2c_dev) ens210_sys_enable(i2c_dev); - k_sleep(2); + k_sleep(K_MSEC(2)); } if (ret < 0) { diff --git a/drivers/sensor/hts221/hts221.c b/drivers/sensor/hts221/hts221.c index 98a8e133e0c54..fde1dedb6623a 100644 --- a/drivers/sensor/hts221/hts221.c +++ b/drivers/sensor/hts221/hts221.c @@ -158,7 +158,7 @@ int hts221_init(struct device *dev) * the device requires about 2.2 ms to download the flash content * into the volatile mem */ - k_sleep(3); + k_sleep(K_MSEC(3)); if (hts221_read_conversion_data(drv_data) < 0) { LOG_ERR("Failed to read conversion data."); diff --git a/drivers/sensor/lsm6dsl/lsm6dsl_shub.c b/drivers/sensor/lsm6dsl/lsm6dsl_shub.c index 3b728b476caa0..8458fc08d1955 100644 --- a/drivers/sensor/lsm6dsl/lsm6dsl_shub.c +++ b/drivers/sensor/lsm6dsl/lsm6dsl_shub.c @@ -65,7 +65,7 @@ static int lsm6dsl_lis2mdl_init(struct lsm6dsl_data *data, u8_t i2c_addr) lsm6dsl_shub_write_slave_reg(data, i2c_addr, LIS2MDL_CFG_REG_A, mag_cfg, 1); - k_sleep(10); /* turn-on time in ms */ + k_sleep(K_MSEC(10)); /* turn-on time in ms */ /* configure mag */ mag_cfg[0] = LIS2MDL_ODR_10HZ; @@ -99,7 +99,7 @@ static int lsm6dsl_lps22hb_init(struct lsm6dsl_data *data, u8_t i2c_addr) lsm6dsl_shub_write_slave_reg(data, i2c_addr, LPS22HB_CTRL_REG2, baro_cfg, 1); - k_sleep(1); /* turn-on time in ms */ + k_sleep(K_MSEC(1)); /* turn-on time in ms */ /* configure device */ baro_cfg[0] = LPS22HB_ODR_10HZ | LPS22HB_LPF_EN | LPS22HB_BDU_EN; @@ -162,7 +162,7 @@ static inline void lsm6dsl_shub_embedded_en(struct lsm6dsl_data *data, bool on) LSM6DSL_MASK_FUNC_CFG_EN, func_en << LSM6DSL_SHIFT_FUNC_CFG_EN); - k_sleep(1); + k_sleep(K_MSEC(1)); } #ifdef LSM6DSL_DEBUG diff --git a/drivers/sensor/lsm6dso/lsm6dso_shub.c b/drivers/sensor/lsm6dso/lsm6dso_shub.c index 91ec61cf465e9..6f7cd22b4eb1d 100644 --- a/drivers/sensor/lsm6dso/lsm6dso_shub.c +++ b/drivers/sensor/lsm6dso/lsm6dso_shub.c @@ -83,7 +83,7 @@ static int lsm6dso_lis2mdl_init(struct lsm6dso_data *data, u8_t i2c_addr) lsm6dso_shub_write_slave_reg(data, i2c_addr, LIS2MDL_CFG_REG_A, mag_cfg, 1); - k_sleep(10); /* turn-on time in ms */ + k_sleep(K_MSEC(10)); /* turn-on time in ms */ /* configure mag */ mag_cfg[0] = LIS2MDL_ODR_10HZ; @@ -254,7 +254,7 @@ static int lsm6dso_lps22hb_init(struct lsm6dso_data *data, u8_t i2c_addr) lsm6dso_shub_write_slave_reg(data, i2c_addr, LPS22HB_CTRL_REG2, baro_cfg, 1); - k_sleep(1); /* turn-on time in ms */ + k_sleep(K_MSEC(1)); /* turn-on time in ms */ /* configure device */ baro_cfg[0] = LPS22HB_ODR_10HZ | LPS22HB_LPF_EN | LPS22HB_BDU_EN; @@ -288,7 +288,7 @@ static int lsm6dso_lps22hh_init(struct lsm6dso_data *data, u8_t i2c_addr) lsm6dso_shub_write_slave_reg(data, i2c_addr, LPS22HH_CTRL_REG2, baro_cfg, 1); - k_sleep(100); /* turn-on time in ms */ + k_sleep(K_MSEC(100)); /* turn-on time in ms */ /* configure device */ baro_cfg[0] = LPS22HH_IF_ADD_INC; diff --git a/drivers/sensor/vl53l0x/vl53l0x.c b/drivers/sensor/vl53l0x/vl53l0x.c index b57f9f85c07d0..78f4c75351396 100644 --- a/drivers/sensor/vl53l0x/vl53l0x.c +++ b/drivers/sensor/vl53l0x/vl53l0x.c @@ -224,7 +224,7 @@ static int vl53l0x_init(struct device *dev) } gpio_pin_write(gpio, CONFIG_VL53L0X_XSHUT_GPIO_PIN_NUM, 1); - k_sleep(100); + k_sleep(K_MSEC(100)); #endif drv_data->i2c = device_get_binding(DT_INST_0_ST_VL53L0X_BUS_NAME); diff --git a/drivers/sensor/vl53l0x/vl53l0x_platform.c b/drivers/sensor/vl53l0x/vl53l0x_platform.c index f88dbd093017c..a51dc8a2e5b97 100644 --- a/drivers/sensor/vl53l0x/vl53l0x_platform.c +++ b/drivers/sensor/vl53l0x/vl53l0x_platform.c @@ -190,7 +190,7 @@ VL53L0X_Error VL53L0X_RdDWord(VL53L0X_DEV Dev, uint8_t index, uint32_t *data) VL53L0X_Error VL53L0X_PollingDelay(VL53L0X_DEV Dev) { - k_sleep(2); + k_sleep(K_MSEC(2)); return VL53L0X_ERROR_NONE; } diff --git a/drivers/usb/device/usb_dc_native_posix_adapt.c b/drivers/usb/device/usb_dc_native_posix_adapt.c index 144d8abe0999b..5d242515113f7 100644 --- a/drivers/usb/device/usb_dc_native_posix_adapt.c +++ b/drivers/usb/device/usb_dc_native_posix_adapt.c @@ -318,7 +318,7 @@ void usbip_start(void) if (connfd < 0) { if (errno == EAGAIN || errno == EWOULDBLOCK) { /* Non-blocking accept */ - k_sleep(100); + k_sleep(K_MSEC(100)); continue; } @@ -347,7 +347,7 @@ void usbip_start(void) if (errno == EAGAIN || errno == EWOULDBLOCK) { /* Non-blocking accept */ - k_sleep(100); + k_sleep(K_MSEC(100)); continue; } @@ -389,7 +389,7 @@ void usbip_start(void) if (read < 0) { if (errno == EAGAIN || errno == EWOULDBLOCK) { /* Non-blocking accept */ - k_sleep(100); + k_sleep(K_MSEC(100)); continue; } diff --git a/drivers/wifi/eswifi/eswifi_bus_spi.c b/drivers/wifi/eswifi/eswifi_bus_spi.c index 723539576c21c..770446007027b 100644 --- a/drivers/wifi/eswifi/eswifi_bus_spi.c +++ b/drivers/wifi/eswifi/eswifi_bus_spi.c @@ -48,7 +48,7 @@ static int eswifi_spi_wait_cmddata_ready(struct eswifi_spi_data *spi) do { /* allow other threads to be scheduled */ - k_sleep(1); + k_sleep(K_MSEC(1)); } while (!eswifi_spi_cmddata_ready(spi) && --max_retries); return max_retries ? 0 : -ETIMEDOUT; @@ -169,7 +169,7 @@ static int eswifi_spi_request(struct eswifi_dev *eswifi, char *cmd, size_t clen, /* Flush remaining data if receiving buffer not large enough */ while (eswifi_spi_cmddata_ready(spi)) { eswifi_spi_read(eswifi, tmp, 2); - k_sleep(1); + k_sleep(K_MSEC(1)); } /* Our device is flagged with SPI_HOLD_ON_CS|SPI_LOCK_ON, release */ diff --git a/drivers/wifi/eswifi/eswifi_core.c b/drivers/wifi/eswifi/eswifi_core.c index 96795cddd1830..253bd8c69b0ef 100644 --- a/drivers/wifi/eswifi/eswifi_core.c +++ b/drivers/wifi/eswifi/eswifi_core.c @@ -39,10 +39,10 @@ static struct eswifi_dev eswifi0; /* static instance */ static int eswifi_reset(struct eswifi_dev *eswifi) { gpio_pin_write(eswifi->resetn.dev, eswifi->resetn.pin, 0); - k_sleep(10); + k_sleep(K_MSEC(10)); gpio_pin_write(eswifi->resetn.dev, eswifi->resetn.pin, 1); gpio_pin_write(eswifi->wakeup.dev, eswifi->wakeup.pin, 1); - k_sleep(500); + k_sleep(K_MSEC(500)); /* fetch the cursor */ return eswifi_request(eswifi, NULL, 0, eswifi->buf, diff --git a/samples/boards/96b_argonkey/sensors/src/main.c b/samples/boards/96b_argonkey/sensors/src/main.c index 44f3ce8520c0f..8a585f45ad67b 100644 --- a/samples/boards/96b_argonkey/sensors/src/main.c +++ b/samples/boards/96b_argonkey/sensors/src/main.c @@ -142,7 +142,7 @@ void main(void) for (i = 0; i < 5; i++) { gpio_pin_write(led1, DT_ALIAS_LED1_GPIOS_PIN, on); - k_sleep(200); + k_sleep(K_MSEC(200)); on = (on == 1) ? 0 : 1; } @@ -350,7 +350,7 @@ void main(void) #endif /* CONFIG_LSM6DSL */ printk("- (%d) (trig_cnt: %d)\n\n", ++cnt, lsm6dsl_trig_cnt); - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/boards/sensortile_box/src/main.c b/samples/boards/sensortile_box/src/main.c index d9525099040b7..64c7decd1c9a5 100644 --- a/samples/boards/sensortile_box/src/main.c +++ b/samples/boards/sensortile_box/src/main.c @@ -260,7 +260,7 @@ void main(void) for (i = 0; i < 6; i++) { gpio_pin_write(led0, DT_ALIAS_LED0_GPIOS_PIN, on); gpio_pin_write(led1, DT_ALIAS_LED1_GPIOS_PIN, !on); - k_sleep(100); + k_sleep(K_MSEC(100)); on = (on == 1) ? 0 : 1; } @@ -441,7 +441,7 @@ void main(void) printk("%d:: iis3dhhc trig %d\n", cnt, iis3dhhc_trig_cnt); #endif - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/display/cfb/src/main.c b/samples/display/cfb/src/main.c index cf632eeecfc7d..27343aaf1f26d 100644 --- a/samples/display/cfb/src/main.c +++ b/samples/display/cfb/src/main.c @@ -83,7 +83,7 @@ void main(void) cfb_framebuffer_finalize(dev); #if defined(CONFIG_ARCH_POSIX) - k_sleep(100); + k_sleep(K_MSEC(100)); #endif } } diff --git a/samples/display/ili9340/src/main.c b/samples/display/ili9340/src/main.c index ac1092a658d52..5cf4de4009a34 100644 --- a/samples/display/ili9340/src/main.c +++ b/samples/display/ili9340/src/main.c @@ -138,6 +138,6 @@ void main(void) if (color > 2) { color = 0; } - k_sleep(500); + k_sleep(K_MSEC(500)); } } diff --git a/samples/display/st7789v/src/main.c b/samples/display/st7789v/src/main.c index cdf3aa090a2e8..1a7704356135d 100644 --- a/samples/display/st7789v/src/main.c +++ b/samples/display/st7789v/src/main.c @@ -167,6 +167,6 @@ void main(void) break; } ++cnt; - k_sleep(100); + k_sleep(K_MSEC(100)); } } diff --git a/samples/drivers/entropy/src/main.c b/samples/drivers/entropy/src/main.c index 5872776a26306..545bfea0b3b67 100644 --- a/samples/drivers/entropy/src/main.c +++ b/samples/drivers/entropy/src/main.c @@ -50,6 +50,6 @@ void main(void) printf("\n"); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/drivers/espi/src/main.c b/samples/drivers/espi/src/main.c index 39dee3374543f..5906690a6a625 100644 --- a/samples/drivers/espi/src/main.c +++ b/samples/drivers/espi/src/main.c @@ -222,7 +222,7 @@ void main(void) { int ret; - k_sleep(500); + k_sleep(K_MSEC(500)); #ifdef CONFIG_ESPI_GPIO_DEV_NEEDED gpio_dev0 = device_get_binding(CONFIG_ESPI_GPIO_DEV0); diff --git a/samples/drivers/ht16k33/src/main.c b/samples/drivers/ht16k33/src/main.c index dd767251cfd55..4f0d264a7db09 100644 --- a/samples/drivers/ht16k33/src/main.c +++ b/samples/drivers/ht16k33/src/main.c @@ -68,7 +68,7 @@ void main(void) "one-by-one"); for (i = 0; i < 128; i++) { led_on(led_dev, i); - k_sleep(100); + k_sleep(K_MSEC(100)); } for (i = 500; i <= 2000; i *= 2) { @@ -81,7 +81,7 @@ void main(void) for (i = 100; i >= 0; i -= 10) { LOG_INF("Setting LED brightness to %d%%", i); led_set_brightness(led_dev, 0, i); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } LOG_INF("Turning all LEDs off and restoring 100%% brightness"); diff --git a/samples/drivers/lcd_hd44780/src/main.c b/samples/drivers/lcd_hd44780/src/main.c index c4156672acf47..4d729653d45ec 100644 --- a/samples/drivers/lcd_hd44780/src/main.c +++ b/samples/drivers/lcd_hd44780/src/main.c @@ -309,7 +309,7 @@ void _pi_lcd_write(struct device *gpio_dev, u8_t bits) void pi_lcd_home(struct device *gpio_dev) { _pi_lcd_command(gpio_dev, LCD_RETURN_HOME); - k_sleep(2); /* wait for 2ms */ + k_sleep(K_MSEC(2)); /* wait for 2ms */ } /** Set curson position */ @@ -332,7 +332,7 @@ void pi_lcd_set_cursor(struct device *gpio_dev, u8_t col, u8_t row) void pi_lcd_clear(struct device *gpio_dev) { _pi_lcd_command(gpio_dev, LCD_CLEAR_DISPLAY); - k_sleep(2); /* wait for 2ms */ + k_sleep(K_MSEC(2)); /* wait for 2ms */ } @@ -470,7 +470,7 @@ void pi_lcd_init(struct device *gpio_dev, u8_t cols, u8_t rows, u8_t dotsize) * above 2.7V before sending commands. Arduino can turn on way * before 4.5V so we'll wait 50 */ - k_sleep(50); + k_sleep(K_MSEC(50)); /* this is according to the hitachi HD44780 datasheet * figure 23/24, pg 45/46 try to set 4/8 bits mode @@ -478,30 +478,30 @@ void pi_lcd_init(struct device *gpio_dev, u8_t cols, u8_t rows, u8_t dotsize) if (lcd_data.disp_func & LCD_8BIT_MODE) { /* 1st try */ _pi_lcd_command(gpio_dev, 0x30); - k_sleep(5); /* wait for 5ms */ + k_sleep(K_MSEC(5)); /* wait for 5ms */ /* 2nd try */ _pi_lcd_command(gpio_dev, 0x30); - k_sleep(5); /* wait for 5ms */ + k_sleep(K_MSEC(5)); /* wait for 5ms */ /* 3rd try */ _pi_lcd_command(gpio_dev, 0x30); - k_sleep(1); /* wait for 1ms */ + k_sleep(K_MSEC(1)); /* wait for 1ms */ /* Set 4bit interface */ _pi_lcd_command(gpio_dev, 0x30); } else { /* 1st try */ _pi_lcd_command(gpio_dev, 0x03); - k_sleep(5); /* wait for 5ms */ + k_sleep(K_MSEC(5)); /* wait for 5ms */ /* 2nd try */ _pi_lcd_command(gpio_dev, 0x03); - k_sleep(5); /* wait for 5ms */ + k_sleep(K_MSEC(5)); /* wait for 5ms */ /* 3rd try */ _pi_lcd_command(gpio_dev, 0x03); - k_sleep(1); /* wait for 1ms */ + k_sleep(K_MSEC(1)); /* wait for 1ms */ /* Set 4bit interface */ _pi_lcd_command(gpio_dev, 0x02); diff --git a/samples/drivers/ps2/src/main.c b/samples/drivers/ps2/src/main.c index 2f75176bc1f78..930721254e0ed 100644 --- a/samples/drivers/ps2/src/main.c +++ b/samples/drivers/ps2/src/main.c @@ -40,7 +40,7 @@ static void saturate_ps2(struct k_timer *timer) LOG_DBG("block host\n"); host_blocked = true; ps2_disable_callback(ps2_0_dev); - k_sleep(500); + k_sleep(K_MSEC(500)); host_blocked = false; ps2_enable_callback(ps2_0_dev); } diff --git a/samples/drivers/watchdog/src/main.c b/samples/drivers/watchdog/src/main.c index 0c4d69a6830e0..c1f21aeb849ea 100644 --- a/samples/drivers/watchdog/src/main.c +++ b/samples/drivers/watchdog/src/main.c @@ -86,7 +86,7 @@ void main(void) for (int i = 0; i < WDT_FEED_TRIES; ++i) { printk("Feeding watchdog...\n"); wdt_feed(wdt, wdt_channel_id); - k_sleep(50); + k_sleep(K_MSEC(50)); } /* Waiting for the SoC reset. */ diff --git a/samples/gui/lvgl/src/main.c b/samples/gui/lvgl/src/main.c index 447483147063e..ebe89eb772668 100644 --- a/samples/gui/lvgl/src/main.c +++ b/samples/gui/lvgl/src/main.c @@ -45,7 +45,7 @@ void main(void) lv_label_set_text(count_label, count_str); } lv_task_handler(); - k_sleep(10); + k_sleep(K_MSEC(10)); ++count; } } diff --git a/samples/net/mqtt_publisher/src/main.c b/samples/net/mqtt_publisher/src/main.c index 9dded7c78deb3..340021658a164 100644 --- a/samples/net/mqtt_publisher/src/main.c +++ b/samples/net/mqtt_publisher/src/main.c @@ -463,6 +463,6 @@ void main(void) while (1) { publisher(); - k_sleep(5000); + k_sleep(K_MSEC(5000)); } } diff --git a/samples/philosophers/src/main.c b/samples/philosophers/src/main.c index d6161cd23e5d9..a150a34e43e30 100644 --- a/samples/philosophers/src/main.c +++ b/samples/philosophers/src/main.c @@ -258,6 +258,6 @@ void main(void) /* Wait a few seconds before main() exit, giving the sample the * opportunity to dump some output before coverage data gets emitted */ - k_sleep(5000); + k_sleep(K_MSEC(5000)); #endif } diff --git a/samples/portability/cmsis_rtos_v2/philosophers/src/main.c b/samples/portability/cmsis_rtos_v2/philosophers/src/main.c index 8c3031e2f12ee..b18024bbde32b 100644 --- a/samples/portability/cmsis_rtos_v2/philosophers/src/main.c +++ b/samples/portability/cmsis_rtos_v2/philosophers/src/main.c @@ -257,6 +257,6 @@ void main(void) /* Wait a few seconds before main() exit, giving the sample the * opportunity to dump some output before coverage data gets emitted */ - k_sleep(5000); + k_sleep(K_MSEC(5000)); #endif } diff --git a/samples/sensor/adt7420/src/main.c b/samples/sensor/adt7420/src/main.c index 10194ccc57b90..571c5c5745baf 100644 --- a/samples/sensor/adt7420/src/main.c +++ b/samples/sensor/adt7420/src/main.c @@ -84,7 +84,7 @@ static void process(struct device *dev) sensor_value_to_double(&temp_val)); if (!IS_ENABLED(CONFIG_ADT7420_TRIGGER)) { - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } } diff --git a/samples/sensor/adxl362/src/main.c b/samples/sensor/adxl362/src/main.c index 746ba634e70b2..b4703a9af3e9b 100644 --- a/samples/sensor/adxl362/src/main.c +++ b/samples/sensor/adxl362/src/main.c @@ -58,7 +58,7 @@ void main(void) if (IS_ENABLED(CONFIG_ADXL362_TRIGGER)) { k_sem_take(&sem, K_FOREVER); } else { - k_sleep(1000); + k_sleep(K_MSEC(1000)); if (sensor_sample_fetch(dev) < 0) { printf("Sample fetch error\n"); return; diff --git a/samples/sensor/adxl372/src/main.c b/samples/sensor/adxl372/src/main.c index 74cad1ea7176d..7b526545556e7 100644 --- a/samples/sensor/adxl372/src/main.c +++ b/samples/sensor/adxl372/src/main.c @@ -104,7 +104,7 @@ void main(void) } if (!IS_ENABLED(CONFIG_ADXL372_TRIGGER)) { - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } } diff --git a/samples/sensor/amg88xx/src/main.c b/samples/sensor/amg88xx/src/main.c index 9c7ad8e97db88..9bcc77875d37b 100644 --- a/samples/sensor/amg88xx/src/main.c +++ b/samples/sensor/amg88xx/src/main.c @@ -105,6 +105,6 @@ void main(void) printk("new sample:\n"); print_buffer(temp_value, ARRAY_SIZE(temp_value)); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/ams_iAQcore/src/main.c b/samples/sensor/ams_iAQcore/src/main.c index b0fcc749718ad..ab2497cd0b1ea 100644 --- a/samples/sensor/ams_iAQcore/src/main.c +++ b/samples/sensor/ams_iAQcore/src/main.c @@ -30,6 +30,6 @@ void main(void) co2.val1, co2.val2, voc.val1, voc.val2); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/apds9960/src/main.c b/samples/sensor/apds9960/src/main.c index a8aae0c93176b..8d5d0cf68bf93 100644 --- a/samples/sensor/apds9960/src/main.c +++ b/samples/sensor/apds9960/src/main.c @@ -63,7 +63,7 @@ void main(void) printk("Waiting for a threshold event\n"); k_sem_take(&sem, K_FOREVER); #else - k_sleep(5000); + k_sleep(K_MSEC(5000)); #endif if (sensor_sample_fetch(dev)) { printk("sensor_sample fetch failed\n"); @@ -81,7 +81,7 @@ void main(void) p_state = DEVICE_PM_LOW_POWER_STATE; device_set_power_state(dev, p_state, NULL, NULL); printk("set low power state for 2s\n"); - k_sleep(2000); + k_sleep(K_MSEC(2000)); p_state = DEVICE_PM_ACTIVE_STATE; device_set_power_state(dev, p_state, NULL, NULL); #endif diff --git a/samples/sensor/bme280/src/main.c b/samples/sensor/bme280/src/main.c index 09adec7db258a..00b9ad1ff44bc 100644 --- a/samples/sensor/bme280/src/main.c +++ b/samples/sensor/bme280/src/main.c @@ -31,6 +31,6 @@ void main(void) temp.val1, temp.val2, press.val1, press.val2, humidity.val1, humidity.val2); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/bme680/src/main.c b/samples/sensor/bme680/src/main.c index ac0582811ce1c..04f800b64863a 100644 --- a/samples/sensor/bme680/src/main.c +++ b/samples/sensor/bme680/src/main.c @@ -17,7 +17,7 @@ void main(void) printf("Device %p name is %s\n", dev, dev->config->name); while (1) { - k_sleep(3000); + k_sleep(K_MSEC(3000)); sensor_sample_fetch(dev); sensor_channel_get(dev, SENSOR_CHAN_AMBIENT_TEMP, &temp); diff --git a/samples/sensor/bmm150/src/main.c b/samples/sensor/bmm150/src/main.c index b18b94f8eb946..b45a1eec57743 100644 --- a/samples/sensor/bmm150/src/main.c +++ b/samples/sensor/bmm150/src/main.c @@ -31,7 +31,7 @@ void do_main(struct device *dev) sensor_value_to_double(&y), sensor_value_to_double(&z)); - k_sleep(500); + k_sleep(K_MSEC(500)); } } diff --git a/samples/sensor/ccs811/src/main.c b/samples/sensor/ccs811/src/main.c index 0ff19b924fed0..b73c0248fb4a2 100644 --- a/samples/sensor/ccs811/src/main.c +++ b/samples/sensor/ccs811/src/main.c @@ -25,7 +25,7 @@ static void do_main(struct device *dev) printk("Voltage: %d.%06dV; Current: %d.%06dA\n\n", voltage.val1, voltage.val2, current.val1, current.val2); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/ens210/src/main.c b/samples/sensor/ens210/src/main.c index 4a9fb1a4a24bc..2efae8ed221c4 100644 --- a/samples/sensor/ens210/src/main.c +++ b/samples/sensor/ens210/src/main.c @@ -30,6 +30,6 @@ void main(void) temperature.val1, temperature.val2, humidity.val1, humidity.val2); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/hts221/src/main.c b/samples/sensor/hts221/src/main.c index 770572d467724..fb6360beef73c 100644 --- a/samples/sensor/hts221/src/main.c +++ b/samples/sensor/hts221/src/main.c @@ -68,7 +68,7 @@ void main(void) while (!IS_ENABLED(CONFIG_HTS221_TRIGGER)) { process_sample(dev); - k_sleep(2000); + k_sleep(K_MSEC(2000)); } k_sleep(K_FOREVER); } diff --git a/samples/sensor/lsm303dlhc/src/main.c b/samples/sensor/lsm303dlhc/src/main.c index c65dbf5a1ab55..ec663fceb6d41 100644 --- a/samples/sensor/lsm303dlhc/src/main.c +++ b/samples/sensor/lsm303dlhc/src/main.c @@ -65,6 +65,6 @@ void main(void) printf("Failed to read accelerometer data\n"); } - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/sensor/lsm6dsl/src/main.c b/samples/sensor/lsm6dsl/src/main.c index fd1e0936544e7..7651de242c9c5 100644 --- a/samples/sensor/lsm6dsl/src/main.c +++ b/samples/sensor/lsm6dsl/src/main.c @@ -174,6 +174,6 @@ void main(void) printk("- (%d) (trig_cnt: %d)\n\n", ++cnt, lsm6dsl_trig_cnt); print_samples = 1; - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/sensor/magn_polling/src/main.c b/samples/sensor/magn_polling/src/main.c index a4f3b7ceb859a..6c0fc59507981 100644 --- a/samples/sensor/magn_polling/src/main.c +++ b/samples/sensor/magn_polling/src/main.c @@ -30,7 +30,7 @@ static void do_main(struct device *dev) sensor_value_to_double(&value_y), sensor_value_to_double(&value_z)); - k_sleep(500); + k_sleep(K_MSEC(500)); } } diff --git a/samples/sensor/max30101/src/main.c b/samples/sensor/max30101/src/main.c index ba11edf3896a6..f1fcef73b4f5b 100644 --- a/samples/sensor/max30101/src/main.c +++ b/samples/sensor/max30101/src/main.c @@ -25,6 +25,6 @@ void main(void) /* Print green LED data*/ printf("GREEN=%d\n", green.val1); - k_sleep(20); + k_sleep(K_MSEC(20)); } } diff --git a/samples/sensor/max44009/src/main.c b/samples/sensor/max44009/src/main.c index 483bb301fad59..1c2d16599ede3 100644 --- a/samples/sensor/max44009/src/main.c +++ b/samples/sensor/max44009/src/main.c @@ -43,6 +43,6 @@ void main(void) lum = val.val1; printk("sensor: lum reading: %d\n", lum); - k_sleep(4000); + k_sleep(K_MSEC(4000)); } } diff --git a/samples/sensor/mcp9808/src/main.c b/samples/sensor/mcp9808/src/main.c index 24912c3d32bea..78c76bcaf8ede 100644 --- a/samples/sensor/mcp9808/src/main.c +++ b/samples/sensor/mcp9808/src/main.c @@ -72,6 +72,6 @@ void main(void) printf("temp: %d.%06d\n", temp.val1, temp.val2); - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/sensor/ms5837/src/main.c b/samples/sensor/ms5837/src/main.c index da79e89d914b1..1611ce6e77aae 100644 --- a/samples/sensor/ms5837/src/main.c +++ b/samples/sensor/ms5837/src/main.c @@ -41,6 +41,6 @@ void main(void) printf("Temperature: %d.%06d, Pressure: %d.%06d\n", temp.val1, temp.val2, press.val1, press.val2); - k_sleep(10000); + k_sleep(K_MSEC(10000)); } } diff --git a/samples/sensor/sht3xd/src/main.c b/samples/sensor/sht3xd/src/main.c index cd06df301aa5d..f81a8d43069d7 100644 --- a/samples/sensor/sht3xd/src/main.c +++ b/samples/sensor/sht3xd/src/main.c @@ -84,6 +84,6 @@ void main(void) sensor_value_to_double(&temp), sensor_value_to_double(&hum)); - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/sensor/sx9500/src/main.c b/samples/sensor/sx9500/src/main.c index 090f3f4d19618..e0e1470c722d2 100644 --- a/samples/sensor/sx9500/src/main.c +++ b/samples/sensor/sx9500/src/main.c @@ -44,7 +44,7 @@ void do_main(struct device *dev) setup_trigger(dev); while (1) { - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } @@ -65,7 +65,7 @@ static void do_main(struct device *dev) ret = sensor_channel_get(dev, SENSOR_CHAN_PROX, &prox_value); printk("prox is %d\n", prox_value.val1); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/th02/src/main.c b/samples/sensor/th02/src/main.c index e5ad9185537a2..d50bc7af6db37 100644 --- a/samples/sensor/th02/src/main.c +++ b/samples/sensor/th02/src/main.c @@ -101,6 +101,6 @@ void main(void) #endif - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/sensor/thermometer/src/main.c b/samples/sensor/thermometer/src/main.c index 2b3cc38e6db9f..56b7e8c08f1d7 100644 --- a/samples/sensor/thermometer/src/main.c +++ b/samples/sensor/thermometer/src/main.c @@ -43,6 +43,6 @@ void main(void) printf("Temperature is %gC\n", sensor_value_to_double(&temp_value)); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/tmp112/src/main.c b/samples/sensor/tmp112/src/main.c index 6c1bbb8425b26..79d48d209c8d3 100644 --- a/samples/sensor/tmp112/src/main.c +++ b/samples/sensor/tmp112/src/main.c @@ -50,7 +50,7 @@ static void do_main(struct device *dev) printk("temp is %d (%d micro)\n", temp_value.val1, temp_value.val2); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/tmp116/src/main.c b/samples/sensor/tmp116/src/main.c index 227c74ae7d835..318bc635618ec 100644 --- a/samples/sensor/tmp116/src/main.c +++ b/samples/sensor/tmp116/src/main.c @@ -37,6 +37,6 @@ void main(void) printk("temp is %d.%d oC\n", temp_value.val1, temp_value.val2); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/sensor/vl53l0x/src/main.c b/samples/sensor/vl53l0x/src/main.c index 586efd7479954..674e3376f91cf 100644 --- a/samples/sensor/vl53l0x/src/main.c +++ b/samples/sensor/vl53l0x/src/main.c @@ -36,6 +36,6 @@ void main(void) &value); printf("distance is %.3fm\n", sensor_value_to_double(&value)); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/shields/x_nucleo_iks01a1/src/main.c b/samples/shields/x_nucleo_iks01a1/src/main.c index 1d23b3b860a02..27f98793c265c 100644 --- a/samples/shields/x_nucleo_iks01a1/src/main.c +++ b/samples/shields/x_nucleo_iks01a1/src/main.c @@ -98,6 +98,6 @@ void main(void) sensor_value_to_double(&accel_xyz[1]), sensor_value_to_double(&accel_xyz[2])); - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/shields/x_nucleo_iks01a2/src/main.c b/samples/shields/x_nucleo_iks01a2/src/main.c index 2b028023e63e1..46abd6f2927aa 100644 --- a/samples/shields/x_nucleo_iks01a2/src/main.c +++ b/samples/shields/x_nucleo_iks01a2/src/main.c @@ -146,6 +146,6 @@ void main(void) sensor_value_to_double(&magn[1]), sensor_value_to_double(&magn[2])); - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/shields/x_nucleo_iks01a3/sensorhub/src/main.c b/samples/shields/x_nucleo_iks01a3/sensorhub/src/main.c index 70ab1348b1ba7..cbc20258c04ff 100644 --- a/samples/shields/x_nucleo_iks01a3/sensorhub/src/main.c +++ b/samples/shields/x_nucleo_iks01a3/sensorhub/src/main.c @@ -290,6 +290,6 @@ void main(void) #endif cnt++; - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/shields/x_nucleo_iks01a3/standard/src/main.c b/samples/shields/x_nucleo_iks01a3/standard/src/main.c index 2653ba57d6b85..a7a0fc9086826 100644 --- a/samples/shields/x_nucleo_iks01a3/standard/src/main.c +++ b/samples/shields/x_nucleo_iks01a3/standard/src/main.c @@ -421,6 +421,6 @@ void main(void) #endif cnt++; - k_sleep(2000); + k_sleep(K_MSEC(2000)); } } diff --git a/samples/subsys/fs/fat_fs/src/main.c b/samples/subsys/fs/fat_fs/src/main.c index b5076039993f2..3bed8291be2f5 100644 --- a/samples/subsys/fs/fat_fs/src/main.c +++ b/samples/subsys/fs/fat_fs/src/main.c @@ -74,7 +74,7 @@ void main(void) } while (1) { - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/samples/subsys/logging/logger/src/main.c b/samples/subsys/logging/logger/src/main.c index 9668b6860253f..0813aabef19a2 100644 --- a/samples/subsys/logging/logger/src/main.c +++ b/samples/subsys/logging/logger/src/main.c @@ -243,7 +243,7 @@ static void external_log_system_showcase(void) static void wait_on_log_flushed(void) { while (log_buffered_cnt()) { - k_sleep(5); + k_sleep(K_MSEC(5)); } } @@ -251,7 +251,7 @@ static void log_demo_thread(void *p1, void *p2, void *p3) { bool usermode = _is_user_context(); - k_sleep(100); + k_sleep(K_MSEC(100)); printk("\n\t---=< RUNNING LOGGER DEMO FROM %s THREAD >=---\n\n", (usermode) ? "USER" : "KERNEL"); diff --git a/samples/subsys/mgmt/mcumgr/smp_svr/src/main.c b/samples/subsys/mgmt/mcumgr/smp_svr/src/main.c index 6f737b018a286..5fcf7894acd98 100644 --- a/samples/subsys/mgmt/mcumgr/smp_svr/src/main.c +++ b/samples/subsys/mgmt/mcumgr/smp_svr/src/main.c @@ -167,7 +167,7 @@ void main(void) * main thread idle while the mcumgr server runs. */ while (1) { - k_sleep(1000); + k_sleep(K_MSEC(1000)); STATS_INC(smp_svr_stats, ticks); } } diff --git a/samples/subsys/usb/cdc_acm/src/main.c b/samples/subsys/usb/cdc_acm/src/main.c index ce4a6472a72f3..2a23f55116a11 100644 --- a/samples/subsys/usb/cdc_acm/src/main.c +++ b/samples/subsys/usb/cdc_acm/src/main.c @@ -91,7 +91,7 @@ void main(void) break; } else { /* Give CPU resources to low priority threads. */ - k_sleep(100); + k_sleep(K_MSEC(100)); } } diff --git a/samples/subsys/usb/cdc_acm_composite/src/main.c b/samples/subsys/usb/cdc_acm_composite/src/main.c index aaeccbebaf151..535ea7422fbe3 100644 --- a/samples/subsys/usb/cdc_acm_composite/src/main.c +++ b/samples/subsys/usb/cdc_acm_composite/src/main.c @@ -136,7 +136,7 @@ void main(void) break; } - k_sleep(100); + k_sleep(K_MSEC(100)); } while (1) { @@ -145,7 +145,7 @@ void main(void) break; } - k_sleep(100); + k_sleep(K_MSEC(100)); } LOG_INF("DTR set, start test"); diff --git a/samples/userspace/shared_mem/src/main.c b/samples/userspace/shared_mem/src/main.c index 0c19f3535481f..4b96b128cf07e 100644 --- a/samples/userspace/shared_mem/src/main.c +++ b/samples/userspace/shared_mem/src/main.c @@ -207,7 +207,7 @@ void enc(void) } /* test for CT flag */ while (fBUFOUT != 0) { - k_sleep(100); + k_sleep(K_MSEC(100)); } /* ct thread has cleared the buffer */ memcpy(&BUFOUT, &enc_ct, SAMP_BLOCKSIZE); @@ -226,7 +226,7 @@ void enc(void) void pt(void) { - k_sleep(2000); + k_sleep(K_MSEC(2000)); while (1) { k_sem_take(&allforone, K_FOREVER); if (fBUFIN == 0) { /* send message to encode */ @@ -245,7 +245,7 @@ void pt(void) fBUFIN = 1; } k_sem_give(&allforone); - k_sleep(5000); + k_sleep(K_MSEC(5000)); } } diff --git a/subsys/console/tty.c b/subsys/console/tty.c index 4451bfc234ef7..b0654bdbf7907 100644 --- a/subsys/console/tty.c +++ b/subsys/console/tty.c @@ -194,7 +194,7 @@ static ssize_t tty_read_unbuf(struct tty_serial *tty, void *buf, size_t size) * of data without extra delays. */ if (res == -1) { - k_sleep(1); + k_sleep(K_MSEC(1)); } } diff --git a/subsys/testsuite/include/timestamp.h b/subsys/testsuite/include/timestamp.h index dd9e64bf8c1b4..d4e29a10be449 100644 --- a/subsys/testsuite/include/timestamp.h +++ b/subsys/testsuite/include/timestamp.h @@ -23,7 +23,7 @@ #endif -#define TICK_SYNCH() k_sleep(1) +#define TICK_SYNCH() k_sleep(K_MSEC(1)) #define OS_GET_TIME() k_cycle_get_32() diff --git a/tests/arch/arm/arm_runtime_nmi/src/arm_runtime_nmi.c b/tests/arch/arm/arm_runtime_nmi/src/arm_runtime_nmi.c index eef08ba6c533c..85cfd2fd419c0 100644 --- a/tests/arch/arm/arm_runtime_nmi/src/arm_runtime_nmi.c +++ b/tests/arch/arm/arm_runtime_nmi/src/arm_runtime_nmi.c @@ -55,7 +55,7 @@ void test_arm_runtime_nmi(void) for (i = 0U; i < 10; i++) { printk("Trigger NMI in 10s: %d s\n", i); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } /* Trigger NMI: Should fire immediately */ diff --git a/tests/benchmarks/boot_time/src/main.c b/tests/benchmarks/boot_time/src/main.c index f85a2956bf7f2..e92e8887f056a 100644 --- a/tests/benchmarks/boot_time/src/main.c +++ b/tests/benchmarks/boot_time/src/main.c @@ -31,7 +31,7 @@ void main(void) /* * Go to sleep for 1 tick in order to timestamp when idle thread halts. */ - k_sleep(1); + k_sleep(K_MSEC(1)); int freq = sys_clock_hw_cycles_per_sec() / 1000000; diff --git a/tests/benchmarks/sched/src/main.c b/tests/benchmarks/sched/src/main.c index b9684f7c221b6..4f5b3f715d5b1 100644 --- a/tests/benchmarks/sched/src/main.c +++ b/tests/benchmarks/sched/src/main.c @@ -108,7 +108,7 @@ void main(void) partner_prio, 0, 0); /* Let it start running and pend */ - k_sleep(100); + k_sleep(K_MSEC(100)); u64_t tot = 0U; u32_t runs = 0U; diff --git a/tests/benchmarks/sys_kernel/src/syskernel.c b/tests/benchmarks/sys_kernel/src/syskernel.c index 9e06f37e50f8a..e2edbaf898876 100644 --- a/tests/benchmarks/sys_kernel/src/syskernel.c +++ b/tests/benchmarks/sys_kernel/src/syskernel.c @@ -149,7 +149,7 @@ void main(void) */ u64_t time_stamp = z_tick_get(); - k_sleep(1); + k_sleep(K_MSEC(1)); u64_t time_stamp_2 = z_tick_get(); diff --git a/tests/benchmarks/timing_info/src/msg_passing_bench.c b/tests/benchmarks/timing_info/src/msg_passing_bench.c index 536a1f7bb0dbe..9feecac3fb90b 100644 --- a/tests/benchmarks/timing_info/src/msg_passing_bench.c +++ b/tests/benchmarks/timing_info/src/msg_passing_bench.c @@ -159,7 +159,7 @@ void msg_passing_bench(void) thread_consumer_get_msgq_w_cxt_switch, NULL, NULL, NULL, 2 /*priority*/, 0, 50); - k_sleep(2000); /* make the main thread sleep */ + k_sleep(K_MSEC(2000)); /* make the main thread sleep */ k_thread_abort(producer_get_w_cxt_switch_tid); __msg_q_get_w_cxt_end_time = (z_arch_timing_value_swap_common); @@ -194,7 +194,7 @@ void msg_passing_bench(void) thread_mbox_sync_put_receive, NULL, NULL, NULL, 1 /*priority*/, 0, 0); - k_sleep(1000); /* make the main thread sleep */ + k_sleep(K_MSEC(1000)); /* make the main thread sleep */ mbox_sync_put_end_time = (z_arch_timing_value_swap_common); /*******************************************************************/ @@ -212,7 +212,7 @@ void msg_passing_bench(void) STACK_SIZE, thread_mbox_sync_get_receive, NULL, NULL, NULL, 2 /*priority*/, 0, 0); - k_sleep(1000); /* make the main thread sleep */ + k_sleep(K_MSEC(1000)); /* make the main thread sleep */ mbox_sync_get_end_time = (z_arch_timing_value_swap_common); /*******************************************************************/ @@ -231,7 +231,7 @@ void msg_passing_bench(void) thread_mbox_async_put_receive, NULL, NULL, NULL, 3 /*priority*/, 0, 0); - k_sleep(1000); /* make the main thread sleep */ + k_sleep(K_MSEC(1000)); /* make the main thread sleep */ /*******************************************************************/ int single_element_buffer = 0, status; diff --git a/tests/benchmarks/timing_info/src/semaphore_bench.c b/tests/benchmarks/timing_info/src/semaphore_bench.c index 74b733c2834e6..5dda5a308d6c7 100644 --- a/tests/benchmarks/timing_info/src/semaphore_bench.c +++ b/tests/benchmarks/timing_info/src/semaphore_bench.c @@ -60,7 +60,7 @@ void semaphore_bench(void) NULL, NULL, NULL, 2 /*priority*/, 0, 0); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /* u64_t test_time1 = z_tsc_read(); */ @@ -76,7 +76,7 @@ void semaphore_bench(void) NULL, NULL, NULL, 2 /*priority*/, 0, 0); - k_sleep(1000); + k_sleep(K_MSEC(1000)); sem_give_end_time = (z_arch_timing_value_swap_common); u32_t sem_give_cycles = sem_give_end_time - sem_give_start_time; diff --git a/tests/benchmarks/timing_info/src/thread_bench.c b/tests/benchmarks/timing_info/src/thread_bench.c index 2f323cd027712..af5fbb2cbaca3 100644 --- a/tests/benchmarks/timing_info/src/thread_bench.c +++ b/tests/benchmarks/timing_info/src/thread_bench.c @@ -141,7 +141,7 @@ void system_thread_bench(void) NULL, NULL, NULL, -1 /*priority*/, 0, 0); - k_sleep(1); + k_sleep(K_MSEC(1)); thread_abort_end_time = (z_arch_timing_value_swap_common); z_arch_timing_swap_end = z_arch_timing_value_swap_common; #if defined(CONFIG_X86) || defined(CONFIG_X86_64) @@ -290,7 +290,7 @@ void heap_malloc_free_bench(void) u32_t sum_malloc = 0U; u32_t sum_free = 0U; - k_sleep(10); + k_sleep(K_MSEC(10)); while (count++ != 100) { TIMING_INFO_PRE_READ(); heap_malloc_start_time = TIMING_INFO_OS_GET_TIME(); diff --git a/tests/benchmarks/timing_info/src/yield_bench.c b/tests/benchmarks/timing_info/src/yield_bench.c index 4bd0c0deaac51..b6b3852b90ee8 100644 --- a/tests/benchmarks/timing_info/src/yield_bench.c +++ b/tests/benchmarks/timing_info/src/yield_bench.c @@ -34,7 +34,7 @@ k_tid_t yield1_tid; void yield_bench(void) { /* Thread yield*/ - k_sleep(10); + k_sleep(K_MSEC(10)); yield0_tid = k_thread_create(&my_thread, my_stack_area, STACK_SIZE, thread_yield0_test, @@ -52,7 +52,7 @@ void yield_bench(void) TIMING_INFO_PRE_READ(); thread_sleep_start_time = TIMING_INFO_OS_GET_TIME(); - k_sleep(1000); + k_sleep(K_MSEC(1000)); thread_sleep_end_time = ((u32_t)z_arch_timing_value_swap_common); u32_t yield_cycles = (thread_end_time - thread_start_time) / 2000U; diff --git a/tests/bluetooth/bsim_bt/bsim_test_app/src/test_connect1.c b/tests/bluetooth/bsim_bt/bsim_test_app/src/test_connect1.c index 262bf2016094d..7fa7785fd5b76 100644 --- a/tests/bluetooth/bsim_bt/bsim_test_app/src/test_connect1.c +++ b/tests/bluetooth/bsim_bt/bsim_test_app/src/test_connect1.c @@ -223,7 +223,7 @@ static void connected(struct bt_conn *conn, u8_t conn_err) } if (encrypt_link) { - k_sleep(500); + k_sleep(K_MSEC(500)); bt_conn_auth_cb_register(&auth_cb_success); err = bt_conn_set_security(conn, BT_SECURITY_L2); if (err) { diff --git a/tests/bluetooth/bsim_bt/bsim_test_app/src/test_empty.c b/tests/bluetooth/bsim_bt/bsim_test_app/src/test_empty.c index f83a6a069cca1..dff6c567e9745 100644 --- a/tests/bluetooth/bsim_bt/bsim_test_app/src/test_empty.c +++ b/tests/bluetooth/bsim_bt/bsim_test_app/src/test_empty.c @@ -36,7 +36,7 @@ static void test_empty_thread(void *p1, void *p2, void *p3) while (1) { printk("A silly demo thread. Iteration %i\n", i++); - k_sleep(100); + k_sleep(K_MSEC(100)); } } diff --git a/tests/boards/native_posix/native_tasks/src/main.c b/tests/boards/native_posix/native_tasks/src/main.c index 242295d3c0776..c842f586f2cd5 100644 --- a/tests/boards/native_posix/native_tasks/src/main.c +++ b/tests/boards/native_posix/native_tasks/src/main.c @@ -64,6 +64,6 @@ NATIVE_TASK(test_hook7, ON_EXIT, 310); void main(void) { - k_sleep(100); + k_sleep(K_MSEC(100)); posix_exit(0); } diff --git a/tests/drivers/clock_control/clock_control_api/src/test_clock_control.c b/tests/drivers/clock_control/clock_control_api/src/test_clock_control.c index 443b5335976ef..56c96464837d4 100644 --- a/tests/drivers/clock_control/clock_control_api/src/test_clock_control.c +++ b/tests/drivers/clock_control/clock_control_api/src/test_clock_control.c @@ -66,7 +66,7 @@ static void test_all_instances(test_func_t func, func(devices[i].name, devices[i].startup_us); tear_down_instance(devices[i].name); /* Allow logs to be printed. */ - k_sleep(100); + k_sleep(K_MSEC(100)); } } } diff --git a/tests/drivers/counter/counter_basic_api/src/test_counter.c b/tests/drivers/counter/counter_basic_api/src/test_counter.c index 3030e737c67b5..19689a7fe4770 100644 --- a/tests/drivers/counter/counter_basic_api/src/test_counter.c +++ b/tests/drivers/counter/counter_basic_api/src/test_counter.c @@ -110,7 +110,7 @@ static void test_all_instances(counter_test_func_t func) func(devices[i]); counter_tear_down_instance(devices[i]); /* Allow logs to be printed. */ - k_sleep(100); + k_sleep(K_MSEC(100)); } } diff --git a/tests/drivers/dma/chan_blen_transfer/src/test_dma.c b/tests/drivers/dma/chan_blen_transfer/src/test_dma.c index 43173cdc4b02b..90571fa195d9a 100644 --- a/tests/drivers/dma/chan_blen_transfer/src/test_dma.c +++ b/tests/drivers/dma/chan_blen_transfer/src/test_dma.c @@ -78,7 +78,7 @@ static int test_task(u32_t chan_id, u32_t blen) TC_PRINT("ERROR: transfer\n"); return TC_FAIL; } - k_sleep(2000); + k_sleep(K_MSEC(2000)); TC_PRINT("%s\n", rx_data); if (strcmp(tx_data, rx_data) != 0) return TC_FAIL; diff --git a/tests/drivers/gpio/gpio_basic_api/src/test_callback_manage.c b/tests/drivers/gpio/gpio_basic_api/src/test_callback_manage.c index f7ecdc59aaa9f..258ab96e6ed01 100644 --- a/tests/drivers/gpio/gpio_basic_api/src/test_callback_manage.c +++ b/tests/drivers/gpio/gpio_basic_api/src/test_callback_manage.c @@ -65,7 +65,7 @@ static void init_callback(struct device *dev, static void trigger_callback(struct device *dev, int enable_cb) { gpio_pin_write(dev, PIN_OUT, 0); - k_sleep(100); + k_sleep(K_MSEC(100)); cb_cnt[0] = 0; cb_cnt[1] = 0; @@ -74,9 +74,9 @@ static void trigger_callback(struct device *dev, int enable_cb) } else { gpio_pin_disable_callback(dev, PIN_IN); } - k_sleep(100); + k_sleep(K_MSEC(100)); gpio_pin_write(dev, PIN_OUT, 1); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } static int test_callback_add_remove(void) @@ -129,7 +129,7 @@ static int test_callback_self_remove(void) init_callback(dev, callback_1, callback_remove_self); gpio_pin_write(dev, PIN_OUT, 0); - k_sleep(100); + k_sleep(K_MSEC(100)); cb_data[0].aux = INT_MAX; cb_data[1].aux = INT_MAX; diff --git a/tests/drivers/gpio/gpio_basic_api/src/test_callback_trigger.c b/tests/drivers/gpio/gpio_basic_api/src/test_callback_trigger.c index 28c01d941d850..3b87ad1c26490 100644 --- a/tests/drivers/gpio/gpio_basic_api/src/test_callback_trigger.c +++ b/tests/drivers/gpio/gpio_basic_api/src/test_callback_trigger.c @@ -79,9 +79,9 @@ static int test_callback(int mode) /* 3. enable callback, trigger PIN_IN interrupt by operate PIN_OUT */ cb_cnt = 0; gpio_pin_enable_callback(dev, PIN_IN); - k_sleep(100); + k_sleep(K_MSEC(100)); gpio_pin_write(dev, PIN_OUT, (mode & GPIO_INT_ACTIVE_HIGH) ? 1 : 0); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /*= checkpoint: check callback is triggered =*/ TC_PRINT("check enabled callback\n"); diff --git a/tests/drivers/gpio/gpio_basic_api/src/test_pin_rw.c b/tests/drivers/gpio/gpio_basic_api/src/test_pin_rw.c index f6b2b0ee91c75..cc359e13766c4 100644 --- a/tests/drivers/gpio/gpio_basic_api/src/test_pin_rw.c +++ b/tests/drivers/gpio/gpio_basic_api/src/test_pin_rw.c @@ -35,7 +35,7 @@ void test_gpio_pin_read_write(void) zassert_true(gpio_pin_write(dev, PIN_OUT, val_write) == 0, "write data fail"); TC_PRINT("write: %" PRIu32 "\n", val_write); - k_sleep(100); + k_sleep(K_MSEC(100)); zassert_true(gpio_pin_read(dev, PIN_IN, &val_read) == 0, "read data fail"); TC_PRINT("read: %" PRIu32 "\n", val_read); diff --git a/tests/drivers/i2c/i2c_api/src/test_i2c.c b/tests/drivers/i2c/i2c_api/src/test_i2c.c index ac71ee2d5453f..64df452962702 100644 --- a/tests/drivers/i2c/i2c_api/src/test_i2c.c +++ b/tests/drivers/i2c/i2c_api/src/test_i2c.c @@ -60,7 +60,7 @@ static int test_gy271(void) return TC_FAIL; } - k_sleep(1); + k_sleep(K_MSEC(1)); datas[0] = 0x03; if (i2c_write(i2c_dev, datas, 1, 0x1E)) { @@ -110,7 +110,7 @@ static int test_burst_gy271(void) return TC_FAIL; } - k_sleep(1); + k_sleep(K_MSEC(1)); (void)memset(datas, 0, sizeof(datas)); diff --git a/tests/drivers/i2s/i2s_api/src/test_i2s_loopback.c b/tests/drivers/i2s/i2s_api/src/test_i2s_loopback.c index b5103e51080d8..df751407f23cd 100644 --- a/tests/drivers/i2s/i2s_api/src/test_i2s_loopback.c +++ b/tests/drivers/i2s/i2s_api/src/test_i2s_loopback.c @@ -426,7 +426,7 @@ void test_i2s_transfer_rx_overrun(void) ret = rx_block_read(dev_i2s, 0); zassert_equal(ret, TC_PASS, NULL); - k_sleep(200); + k_sleep(K_MSEC(200)); } /** @brief TX buffer underrun. @@ -463,7 +463,7 @@ void test_i2s_transfer_tx_underrun(void) ret = rx_block_read(dev_i2s, 0); zassert_equal(ret, TC_PASS, NULL); - k_sleep(200); + k_sleep(K_MSEC(200)); /* Write one more TX data block, expect an error */ ret = tx_block_write(dev_i2s, 2, -EIO); @@ -472,7 +472,7 @@ void test_i2s_transfer_tx_underrun(void) ret = i2s_trigger(dev_i2s, I2S_DIR_TX, I2S_TRIGGER_PREPARE); zassert_equal(ret, 0, "TX PREPARE trigger failed"); - k_sleep(200); + k_sleep(K_MSEC(200)); /* Transmit and receive two more data blocks */ ret = tx_block_write(dev_i2s, 1, 0); @@ -492,5 +492,5 @@ void test_i2s_transfer_tx_underrun(void) ret = rx_block_read(dev_i2s, 1); zassert_equal(ret, TC_PASS, NULL); - k_sleep(200); + k_sleep(K_MSEC(200)); } diff --git a/tests/drivers/i2s/i2s_api/src/test_i2s_states.c b/tests/drivers/i2s/i2s_api/src/test_i2s_states.c index 987748c1a2488..52206db4294c0 100644 --- a/tests/drivers/i2s/i2s_api/src/test_i2s_states.c +++ b/tests/drivers/i2s/i2s_api/src/test_i2s_states.c @@ -417,5 +417,5 @@ void test_i2s_state_error_neg(void) ret = rx_block_read(dev_i2s, 0); zassert_equal(ret, TC_PASS, NULL); - k_sleep(200); + k_sleep(K_MSEC(200)); } diff --git a/tests/drivers/pinmux/pinmux_basic_api/src/pinmux_gpio.c b/tests/drivers/pinmux/pinmux_basic_api/src/pinmux_gpio.c index fbf0badd6a6f4..c0b94e3bf17e3 100644 --- a/tests/drivers/pinmux/pinmux_basic_api/src/pinmux_gpio.c +++ b/tests/drivers/pinmux/pinmux_basic_api/src/pinmux_gpio.c @@ -112,7 +112,7 @@ static int test_gpio(u32_t pin, u32_t func) return TC_FAIL; } - k_sleep(1000); + k_sleep(K_MSEC(1000)); if (cb_triggered) { TC_PRINT("GPIO callback is triggered\n"); diff --git a/tests/drivers/pwm/pwm_api/src/test_pwm.c b/tests/drivers/pwm/pwm_api/src/test_pwm.c index 410701f1a678b..a78dc27bdbb6d 100644 --- a/tests/drivers/pwm/pwm_api/src/test_pwm.c +++ b/tests/drivers/pwm/pwm_api/src/test_pwm.c @@ -110,17 +110,17 @@ void test_pwm_usec(void) /* Period : Pulse (2000 : 1000), unit (usec). Voltage : 1.65V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_USEC, DEFAULT_PULSE_USEC, UNIT_USECS) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /* Period : Pulse (2000 : 2000), unit (usec). Voltage : 3.3V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_USEC, DEFAULT_PERIOD_USEC, UNIT_USECS) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /* Period : Pulse (2000 : 0), unit (usec). Voltage : 0V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_USEC, 0, UNIT_USECS) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } void test_pwm_nsec(void) @@ -128,17 +128,17 @@ void test_pwm_nsec(void) /* Period : Pulse (2000000 : 1000000), unit (nsec). Voltage : 1.65V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_NSEC, DEFAULT_PULSE_NSEC, UNIT_NSECS) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /* Period : Pulse (2000000 : 2000000), unit (nsec). Voltage : 3.3V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_NSEC, DEFAULT_PERIOD_NSEC, UNIT_NSECS) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /* Period : Pulse (2000000 : 0), unit (nsec). Voltage : 0V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_NSEC, 0, UNIT_NSECS) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); } void test_pwm_cycle(void) @@ -146,12 +146,12 @@ void test_pwm_cycle(void) /* Period : Pulse (64000 : 32000), unit (cycle). Voltage : 1.65V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_CYCLE, DEFAULT_PULSE_CYCLE, UNIT_CYCLES) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /* Period : Pulse (64000 : 64000), unit (cycle). Voltage : 3.3V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_CYCLE, DEFAULT_PERIOD_CYCLE, UNIT_CYCLES) == TC_PASS, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); /* Period : Pulse (64000 : 0), unit (cycle). Voltage : 0V */ zassert_true(test_task(DEFAULT_PWM_PORT, DEFAULT_PERIOD_CYCLE, diff --git a/tests/drivers/uart/uart_basic_api/src/test_uart_fifo.c b/tests/drivers/uart/uart_basic_api/src/test_uart_fifo.c index 04c8e6f0b114e..00805bd66db63 100644 --- a/tests/drivers/uart/uart_basic_api/src/test_uart_fifo.c +++ b/tests/drivers/uart/uart_basic_api/src/test_uart_fifo.c @@ -124,7 +124,7 @@ static int test_fifo_fill(void) /* Verify uart_irq_tx_enable() */ uart_irq_tx_enable(uart_dev); - k_sleep(500); + k_sleep(K_MSEC(500)); /* Verify uart_irq_tx_disable() */ uart_irq_tx_disable(uart_dev); diff --git a/tests/drivers/watchdog/wdt_basic_api/src/test_wdt.c b/tests/drivers/watchdog/wdt_basic_api/src/test_wdt.c index 1b4fd79eded70..d2ffb38f3f587 100644 --- a/tests/drivers/watchdog/wdt_basic_api/src/test_wdt.c +++ b/tests/drivers/watchdog/wdt_basic_api/src/test_wdt.c @@ -274,7 +274,7 @@ static int test_wdt_callback_2(void) while (1) { wdt_feed(wdt, 0); - k_sleep(100); + k_sleep(K_MSEC(100)); }; } #endif diff --git a/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c b/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c index ead5996320401..d743c43d346e6 100644 --- a/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c +++ b/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c @@ -18,7 +18,7 @@ static struct k_thread thread; static void t_cancel_wait_entry(void *p1, void *p2, void *p3) { - k_sleep(50); + k_sleep(K_MSEC(50)); k_fifo_cancel_wait((struct k_fifo *)p1); } diff --git a/tests/kernel/fifo/fifo_timeout/src/main.c b/tests/kernel/fifo/fifo_timeout/src/main.c index d8ec1e1318cb6..c7bb011ca0f44 100644 --- a/tests/kernel/fifo/fifo_timeout/src/main.c +++ b/tests/kernel/fifo/fifo_timeout/src/main.c @@ -124,7 +124,7 @@ static void test_thread_pend_and_timeout(void *p1, void *p2, void *p3) u32_t start_time; void *packet; - k_sleep(1); /* Align to ticks */ + k_sleep(K_MSEC(1)); /* Align to ticks */ start_time = k_cycle_get_32(); packet = k_fifo_get(d->fifo, d->timeout); @@ -300,7 +300,7 @@ static void test_timeout_empty_fifo(void) void *packet; u32_t start_time, timeout; - k_sleep(1); /* Align to ticks */ + k_sleep(K_MSEC(1)); /* Align to ticks */ /* Test empty fifo with timeout */ timeout = 10U; @@ -353,7 +353,7 @@ static void test_timeout_fifo_thread(void) struct reply_packet reply_packet; u32_t start_time, timeout; - k_sleep(1); /* Align to ticks */ + k_sleep(K_MSEC(1)); /* Align to ticks */ /* * Test fifo with some timeout and child thread that puts diff --git a/tests/kernel/fp_sharing/generic/src/main.c b/tests/kernel/fp_sharing/generic/src/main.c index 62ad3dab27ea9..136b7e69324aa 100644 --- a/tests/kernel/fp_sharing/generic/src/main.c +++ b/tests/kernel/fp_sharing/generic/src/main.c @@ -331,7 +331,7 @@ void load_store_high(void) * once the sleep ends. */ - k_sleep(1); + k_sleep(K_MSEC(1)); /* periodically issue progress report */ @@ -380,6 +380,6 @@ void main(void *p1, void *p2, void *p3) * gcov manually later when the test completes. */ while (true) { - k_sleep(1000); + k_sleep(K_MSEC(1000)); } } diff --git a/tests/kernel/fp_sharing/generic/src/pi.c b/tests/kernel/fp_sharing/generic/src/pi.c index 65f07864b1612..3000c23b5beb0 100644 --- a/tests/kernel/fp_sharing/generic/src/pi.c +++ b/tests/kernel/fp_sharing/generic/src/pi.c @@ -134,7 +134,7 @@ void calculate_pi_high(void) * once the sleep ends. */ - k_sleep(10); + k_sleep(K_MSEC(10)); pi *= 4; diff --git a/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c b/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c index 2b0ceb55d0f0a..032170b0e8d38 100644 --- a/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c +++ b/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c @@ -80,7 +80,7 @@ void test_mpool_alloc_wait_prio(void) tmpool_alloc_wait_timeout, NULL, NULL, NULL, K_PRIO_PREEMPT(0), 0, 20); /*relinquish CPU for above threads to start */ - k_sleep(30); + k_sleep(K_MSEC(30)); /*free one block, expected to unblock thread "tid[1]"*/ k_mem_pool_free(&block[0]); /*wait for all threads exit*/ diff --git a/tests/kernel/mem_protect/userspace/src/main.c b/tests/kernel/mem_protect/userspace/src/main.c index 5ec692bfd0791..0c05bd60b9c38 100644 --- a/tests/kernel/mem_protect/userspace/src/main.c +++ b/tests/kernel/mem_protect/userspace/src/main.c @@ -696,7 +696,7 @@ static void domain_add_thread_drop_to_user(void) k_mem_domain_init(&add_thread_drop_dom, ARRAY_SIZE(parts), parts); k_mem_domain_remove_thread(k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_add_thread(&add_thread_drop_dom, k_current_get()); k_thread_user_mode_enter(user_half, NULL, NULL, NULL); @@ -716,7 +716,7 @@ static void domain_add_part_drop_to_user(void) k_mem_domain_remove_thread(k_current_get()); k_mem_domain_add_thread(&add_part_drop_dom, k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_add_partition(&add_part_drop_dom, &access_part); k_thread_user_mode_enter(user_half, NULL, NULL, NULL); @@ -738,7 +738,7 @@ static void domain_remove_thread_drop_to_user(void) k_mem_domain_remove_thread(k_current_get()); k_mem_domain_add_thread(&remove_thread_drop_dom, k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_remove_thread(k_current_get()); k_thread_user_mode_enter(user_half, NULL, NULL, NULL); @@ -761,7 +761,7 @@ static void domain_remove_part_drop_to_user(void) k_mem_domain_remove_thread(k_current_get()); k_mem_domain_add_thread(&remove_part_drop_dom, k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_remove_partition(&remove_part_drop_dom, &access_part); k_thread_user_mode_enter(user_half, NULL, NULL, NULL); @@ -804,7 +804,7 @@ static void domain_add_thread_context_switch(void) k_mem_domain_init(&add_thread_ctx_dom, ARRAY_SIZE(parts), parts); k_mem_domain_remove_thread(k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_add_thread(&add_thread_ctx_dom, k_current_get()); spawn_user(); @@ -824,7 +824,7 @@ static void domain_add_part_context_switch(void) k_mem_domain_remove_thread(k_current_get()); k_mem_domain_add_thread(&add_part_ctx_dom, k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_add_partition(&add_part_ctx_dom, &access_part); spawn_user(); @@ -846,7 +846,7 @@ static void domain_remove_thread_context_switch(void) k_mem_domain_remove_thread(k_current_get()); k_mem_domain_add_thread(&remove_thread_ctx_dom, k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_remove_thread(k_current_get()); spawn_user(); @@ -870,7 +870,7 @@ static void domain_remove_part_context_switch(void) k_mem_domain_remove_thread(k_current_get()); k_mem_domain_add_thread(&remove_part_ctx_dom, k_current_get()); - k_sleep(1); + k_sleep(K_MSEC(1)); k_mem_domain_remove_partition(&remove_part_ctx_dom, &access_part); spawn_user(); diff --git a/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c b/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c index cf278f9ffc6f1..90e5034faa759 100644 --- a/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c +++ b/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c @@ -82,7 +82,7 @@ void test_mslab_alloc_wait_prio(void) tmslab_alloc_wait_timeout, NULL, NULL, NULL, K_PRIO_PREEMPT(0), 0, 20); /*relinquish CPU for above threads to start */ - k_sleep(30); + k_sleep(K_MSEC(30)); /*free one block, expected to unblock thread "tid[1]"*/ k_mem_slab_free(&mslab1, &block[0]); /*wait for all threads exit*/ diff --git a/tests/kernel/mutex/sys_mutex/src/main.c b/tests/kernel/mutex/sys_mutex/src/main.c index e35876849068c..c577230b497ba 100644 --- a/tests/kernel/mutex/sys_mutex/src/main.c +++ b/tests/kernel/mutex/sys_mutex/src/main.c @@ -345,7 +345,7 @@ void test_mutex(void) k_thread_create(&thread_12_thread_data, thread_12_stack_area, STACKSIZE, (k_thread_entry_t)thread_12, NULL, NULL, NULL, K_PRIO_PREEMPT(12), thread_flags, K_NO_WAIT); - k_sleep(1); /* Give thread_12 a chance to block on the mutex */ + k_sleep(K_MSEC(1)); /* Give thread_12 a chance to block on the mutex */ sys_mutex_unlock(&private_mutex); sys_mutex_unlock(&private_mutex); /* thread_12 should now have lock */ diff --git a/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c b/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c index 0d1cb0f5bd6a2..fa1df8cb22a44 100644 --- a/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c +++ b/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c @@ -212,7 +212,7 @@ void test_pipe_block_put(void) tThread_block_put, &kpipe, NULL, NULL, K_PRIO_PREEMPT(0), 0, 0); - k_sleep(10); + k_sleep(K_MSEC(10)); tpipe_get(&kpipe, K_FOREVER); k_sem_take(&end_sema, K_FOREVER); @@ -232,7 +232,7 @@ void test_pipe_block_put_sema(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_block_put, &pipe, &sync_sema, NULL, K_PRIO_PREEMPT(0), 0, 0); - k_sleep(10); + k_sleep(K_MSEC(10)); tpipe_get(&pipe, K_FOREVER); k_sem_take(&end_sema, K_FOREVER); @@ -315,7 +315,7 @@ void test_half_pipe_block_put_sema(void) &khalfpipe, &sync_sema, NULL, K_PRIO_PREEMPT(0), 0, 0); - k_sleep(10); + k_sleep(K_MSEC(10)); tpipe_get(&khalfpipe, K_FOREVER); k_thread_abort(tid); diff --git a/tests/kernel/poll/src/test_poll.c b/tests/kernel/poll/src/test_poll.c index 1a4fe5928877f..680787a81a42d 100644 --- a/tests/kernel/poll/src/test_poll.c +++ b/tests/kernel/poll/src/test_poll.c @@ -173,7 +173,7 @@ static void poll_wait_helper(void *use_fifo, void *p2, void *p3) { (void)p2; (void)p3; - k_sleep(250); + k_sleep(K_MSEC(250)); k_sem_give(&wait_sem); @@ -377,7 +377,7 @@ static void poll_cancel_helper(void *p1, void *p2, void *p3) static struct fifo_msg msg; - k_sleep(100); + k_sleep(K_MSEC(100)); k_fifo_cancel_wait(&cancel_fifo); @@ -531,7 +531,7 @@ void test_poll_multi(void) K_USER | K_INHERIT_PERMS, 0); /* Allow lower priority thread to add poll event in the list */ - k_sleep(250); + k_sleep(K_MSEC(250)); rc = k_poll(events, ARRAY_SIZE(events), K_SECONDS(1)); zassert_equal(rc, 0, ""); @@ -547,7 +547,7 @@ void test_poll_multi(void) /* wait for polling threads to complete execution */ k_thread_priority_set(k_current_get(), old_prio); - k_sleep(250); + k_sleep(K_MSEC(250)); } static struct k_poll_signal signal; @@ -556,7 +556,7 @@ static void threadstate(void *p1, void *p2, void *p3) { (void)p2; (void)p3; - k_sleep(250); + k_sleep(K_MSEC(250)); /* Update polling thread state explicitly to improve code coverage */ k_thread_suspend(p1); /* Enable polling thread by signalling */ diff --git a/tests/kernel/queue/src/test_queue_contexts.c b/tests/kernel/queue/src/test_queue_contexts.c index d32935773e74b..0b35e6f6c88a8 100644 --- a/tests/kernel/queue/src/test_queue_contexts.c +++ b/tests/kernel/queue/src/test_queue_contexts.c @@ -199,7 +199,7 @@ static void tqueue_get_2threads(struct k_queue *pqueue) K_PRIO_PREEMPT(0), 0, 0); /* Wait threads to initialize */ - k_sleep(10); + k_sleep(K_MSEC(10)); k_queue_append(pqueue, (void *)&data[0]); k_queue_append(pqueue, (void *)&data[1]); diff --git a/tests/kernel/sched/deadline/src/main.c b/tests/kernel/sched/deadline/src/main.c index 2369e2197258e..67f7937cf0b80 100644 --- a/tests/kernel/sched/deadline/src/main.c +++ b/tests/kernel/sched/deadline/src/main.c @@ -39,7 +39,7 @@ void worker(void *p1, void *p2, void *p3) * with the scheduling. */ while (1) { - k_sleep(1000000); + k_sleep(K_MSEC(1000000)); } } @@ -78,7 +78,7 @@ void test_deadline(void) zassert_true(n_exec == 0, "threads ran too soon"); - k_sleep(100); + k_sleep(K_MSEC(100)); zassert_true(n_exec == NUM_THREADS, "not enough threads ran"); diff --git a/tests/kernel/sched/preempt/src/main.c b/tests/kernel/sched/preempt/src/main.c index df65df964d6c2..9fc961aafb30f 100644 --- a/tests/kernel/sched/preempt/src/main.c +++ b/tests/kernel/sched/preempt/src/main.c @@ -291,7 +291,7 @@ void worker(void *p1, void *p2, void *p3) if (do_sleep) { u64_t start = k_uptime_get(); - k_sleep(1); + k_sleep(K_MSEC(1)); zassert_true(k_uptime_get() - start > 0, "didn't sleep"); diff --git a/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c b/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c index 2e4a01f8d3012..176575e0d7266 100644 --- a/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c +++ b/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c @@ -90,7 +90,7 @@ void test_priority_scheduling(void) k_sem_take(&sema2, K_FOREVER); } /* Delay to give chance to last thread to run */ - k_sleep(1); + k_sleep(K_MSEC(1)); /* Giving Chance to other threads to run */ for (int i = 0; i < NUM_THREAD; i++) { diff --git a/tests/kernel/sched/schedule_api/src/test_sched_priority.c b/tests/kernel/sched/schedule_api/src/test_sched_priority.c index 4d0dc9183f76e..eb3e47263bfcc 100644 --- a/tests/kernel/sched/schedule_api/src/test_sched_priority.c +++ b/tests/kernel/sched/schedule_api/src/test_sched_priority.c @@ -44,7 +44,7 @@ void test_priority_cooperative(void) spawn_prio, 0, 0); /* checkpoint: current thread shouldn't preempted by higher thread */ zassert_true(last_prio == k_thread_priority_get(k_current_get()), NULL); - k_sleep(100); + k_sleep(K_MSEC(100)); /* checkpoint: spawned thread get executed */ zassert_true(last_prio == spawn_prio, NULL); k_thread_abort(tid); @@ -80,7 +80,7 @@ void test_priority_preemptible(void) /* checkpoint: thread is preempted by higher thread */ zassert_true(last_prio == spawn_prio, NULL); - k_sleep(100); + k_sleep(K_MSEC(100)); k_thread_abort(tid); spawn_prio = last_prio + 1; diff --git a/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c b/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c index 8beef22948696..dc9a916aba88e 100644 --- a/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c +++ b/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c @@ -130,7 +130,7 @@ void test_sleep_cooperative(void) spawn_threads(0); /* checkpoint: all ready threads get executed when k_sleep */ - k_sleep(100); + k_sleep(K_MSEC(100)); for (int i = 0; i < THREADS_NUM; i++) { zassert_true(tdata[i].executed == 1, NULL); } @@ -324,7 +324,7 @@ void test_lock_preemptible(void) zassert_true(tdata[i].executed == 0, NULL); } /* make current thread unready */ - k_sleep(100); + k_sleep(K_MSEC(100)); /* checkpoint: all other threads get executed */ for (int i = 0; i < THREADS_NUM; i++) { zassert_true(tdata[i].executed == 1, NULL); diff --git a/tests/kernel/smp/src/main.c b/tests/kernel/smp/src/main.c index a300ec1bfeab6..0018ae2358654 100644 --- a/tests/kernel/smp/src/main.c +++ b/tests/kernel/smp/src/main.c @@ -138,7 +138,7 @@ static void child_fn(void *p1, void *p2, void *p3) void test_cpu_id_threads(void) { /* Make sure idle thread runs on each core */ - k_sleep(1000); + k_sleep(K_MSEC(1000)); int parent_cpu_id = z_arch_curr_cpu()->id; @@ -436,7 +436,7 @@ void test_main(void) * thread from which they can exit correctly to run the main * test. */ - k_sleep(1000); + k_sleep(K_MSEC(1000)); ztest_test_suite(smp, ztest_unit_test(test_smp_coop_threads), diff --git a/tests/kernel/threads/thread_apis/src/main.c b/tests/kernel/threads/thread_apis/src/main.c index 940c30f06990a..9c3f5067c5cd6 100644 --- a/tests/kernel/threads/thread_apis/src/main.c +++ b/tests/kernel/threads/thread_apis/src/main.c @@ -64,7 +64,7 @@ void test_systhreads_main(void) */ void test_systhreads_idle(void) { - k_sleep(100); + k_sleep(K_MSEC(100)); /** TESTPOINT: check working thread priority should */ zassert_true(k_thread_priority_get(k_current_get()) < K_IDLE_PRIO, NULL); @@ -78,7 +78,7 @@ static void customdata_entry(void *p1, void *p2, void *p3) while (1) { k_thread_custom_data_set((void *)data); /* relinguish cpu for a while */ - k_sleep(50); + k_sleep(K_MSEC(50)); /** TESTPOINT: custom data comparison */ zassert_equal(data, (long)k_thread_custom_data_get(), NULL); data++; @@ -97,7 +97,7 @@ void test_customdata_get_set_coop(void) customdata_entry, NULL, NULL, NULL, K_PRIO_COOP(1), 0, 0); - k_sleep(500); + k_sleep(K_MSEC(500)); /* cleanup environment */ k_thread_abort(tid); @@ -225,7 +225,7 @@ void test_customdata_get_set_preempt(void) customdata_entry, NULL, NULL, NULL, K_PRIO_PREEMPT(0), K_USER, 0); - k_sleep(500); + k_sleep(K_MSEC(500)); /* cleanup environment */ k_thread_abort(tid); diff --git a/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c b/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c index a13fc8f8363ba..d7c479a120a00 100644 --- a/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c +++ b/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c @@ -63,7 +63,7 @@ void test_k_thread_foreach(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, (k_thread_entry_t)thread_entry, NULL, NULL, NULL, K_PRIO_PREEMPT(0), 0, 0); - k_sleep(1); + k_sleep(K_MSEC(1)); /* Call k_thread_foreach() and check * thread_callback is getting called for diff --git a/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c b/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c index 181e8dec91645..4cc1edd90cf50 100644 --- a/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c +++ b/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c @@ -16,7 +16,7 @@ K_SEM_DEFINE(sync_sema, 0, 1); static void thread_entry(void *p1, void *p2, void *p3) { execute_flag = 1; - k_sleep(100); + k_sleep(K_MSEC(100)); execute_flag = 2; } @@ -44,7 +44,7 @@ void test_threads_abort_self(void) execute_flag = 0; k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_abort, NULL, NULL, NULL, 0, K_USER, 0); - k_sleep(100); + k_sleep(K_MSEC(100)); /**TESTPOINT: spawned thread executed but abort itself*/ zassert_true(execute_flag == 1, NULL); } @@ -67,18 +67,18 @@ void test_threads_abort_others(void) 0, K_USER, 0); k_thread_abort(tid); - k_sleep(100); + k_sleep(K_MSEC(100)); /**TESTPOINT: check not-started thread is aborted*/ zassert_true(execute_flag == 0, NULL); tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, 0, K_USER, 0); - k_sleep(50); + k_sleep(K_MSEC(50)); k_thread_abort(tid); /**TESTPOINT: check running thread is aborted*/ zassert_true(execute_flag == 1, NULL); - k_sleep(1000); + k_sleep(K_MSEC(1000)); zassert_true(execute_flag == 1, NULL); } @@ -96,9 +96,9 @@ void test_threads_abort_repeat(void) 0, K_USER, 0); k_thread_abort(tid); - k_sleep(100); + k_sleep(K_MSEC(100)); k_thread_abort(tid); - k_sleep(100); + k_sleep(K_MSEC(100)); k_thread_abort(tid); /* If no fault occurred till now. The test case passed. */ ztest_test_pass(); @@ -177,7 +177,7 @@ void test_delayed_thread_abort(void) K_PRIO_PREEMPT(1), 0, 100); /* Give up CPU */ - k_sleep(50); + k_sleep(K_MSEC(50)); /* Test point: check if thread delayed for 100ms has not started*/ zassert_true(execute_flag == 0, "Delayed thread created is not" diff --git a/tests/kernel/threads/thread_apis/src/test_threads_spawn.c b/tests/kernel/threads/thread_apis/src/test_threads_spawn.c index 63f51439e5194..4b9c15daa4f6f 100644 --- a/tests/kernel/threads/thread_apis/src/test_threads_spawn.c +++ b/tests/kernel/threads/thread_apis/src/test_threads_spawn.c @@ -50,7 +50,7 @@ void test_threads_spawn_params(void) k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_params, tp1, INT_TO_POINTER(tp2), tp3, 0, K_USER, 0); - k_sleep(100); + k_sleep(K_MSEC(100)); } /** @@ -68,7 +68,7 @@ void test_threads_spawn_priority(void) spawn_prio = k_thread_priority_get(k_current_get()) - 1; k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_priority, NULL, NULL, NULL, spawn_prio, K_USER, 0); - k_sleep(100); + k_sleep(K_MSEC(100)); } /** @@ -87,11 +87,11 @@ void test_threads_spawn_delay(void) k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_delay, NULL, NULL, NULL, 0, K_USER, 120); /* 100 < 120 ensure spawn thread not start */ - k_sleep(100); + k_sleep(K_MSEC(100)); /* checkpoint: check spawn thread not execute */ zassert_true(tp2 == 10, NULL); /* checkpoint: check spawn thread executed */ - k_sleep(100); + k_sleep(K_MSEC(100)); zassert_true(tp2 == 100, NULL); } diff --git a/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c b/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c index fe1c6f730fe19..25d517b0b524c 100644 --- a/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c +++ b/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c @@ -29,11 +29,11 @@ static void threads_suspend_resume(int prio) create_prio, K_USER, 0); /* checkpoint: suspend current thread */ k_thread_suspend(tid); - k_sleep(100); + k_sleep(K_MSEC(100)); /* checkpoint: created thread shouldn't be executed after suspend */ zassert_false(last_prio == create_prio, NULL); k_thread_resume(tid); - k_sleep(100); + k_sleep(K_MSEC(100)); /* checkpoint: created thread should be executed after resume */ zassert_true(last_prio == create_prio, NULL); } diff --git a/tests/kernel/tickless/tickless/src/main.c b/tests/kernel/tickless/tickless/src/main.c index 03e3fad9b6a73..473585e824620 100644 --- a/tests/kernel/tickless/tickless/src/main.c +++ b/tests/kernel/tickless/tickless/src/main.c @@ -231,7 +231,7 @@ void test_tickless(void) (k_thread_entry_t) ticklessTestThread, NULL, NULL, NULL, PRIORITY, 0, K_NO_WAIT); - k_sleep(4000); + k_sleep(K_MSEC(4000)); } /** diff --git a/tests/kernel/timer/timer_monotonic/src/main.c b/tests/kernel/timer/timer_monotonic/src/main.c index c7f95dbde7ea7..393724da28b76 100644 --- a/tests/kernel/timer/timer_monotonic/src/main.c +++ b/tests/kernel/timer/timer_monotonic/src/main.c @@ -15,7 +15,7 @@ int test_frequency(void) TC_PRINT("Testing system tick frequency\n"); start = k_cycle_get_32(); - k_sleep(1000); + k_sleep(K_MSEC(1000)); end = k_cycle_get_32(); delta = end - start; diff --git a/tests/subsys/settings/fcb_init/src/settings_test_fcb_init.c b/tests/subsys/settings/fcb_init/src/settings_test_fcb_init.c index 43a28c6525892..3202ddbdb7e78 100644 --- a/tests/subsys/settings/fcb_init/src/settings_test_fcb_init.c +++ b/tests/subsys/settings/fcb_init/src/settings_test_fcb_init.c @@ -136,7 +136,7 @@ void test_init_setup(void) val32 = 1U; err = settings_save(); zassert_true(err == 0, "can't save settings"); - k_sleep(250); + k_sleep(K_MSEC(250)); sys_reboot(SYS_REBOOT_COLD); } } From 43dff8a6630a1dd569e8907da7c96cc7420e7cf0 Mon Sep 17 00:00:00 2001 From: Peter Bigot Date: Sun, 6 Oct 2019 14:04:49 -0500 Subject: [PATCH 5/6] scripts/coccinelle: add k_thread create/define to timeout standardization k_thread_create and K_THREAD_DEFINE both take a delay as the final parameter. Most uses of K_THREAD_DEFINE pass either `K_NO_WAIT` or `K_FOREVER`. Ensure that all uses of K_THREAD_DEFINE follow that practice, and that the runtime k_thread_create calls do so as well. Signed-off-by: Peter Bigot --- .../coccinelle/int_literal_to_timeout.cocci | 50 +++++++++++++++++++ 1 file changed, 50 insertions(+) diff --git a/scripts/coccinelle/int_literal_to_timeout.cocci b/scripts/coccinelle/int_literal_to_timeout.cocci index e0ab0748bbfef..76ad76e2e2827 100644 --- a/scripts/coccinelle/int_literal_to_timeout.cocci +++ b/scripts/coccinelle/int_literal_to_timeout.cocci @@ -30,6 +30,7 @@ identifier last_timeout =~ "(?x)^k_ | sem_take | sleep | stack_pop +| thread_create | timer_start | work_poll_submit(|_to_queue) )$"; @@ -87,6 +88,55 @@ C << r_last_timeout_const_report.C; msg = "WARNING: replace constant {} with timeout in {}".format(C, fn) coccilib.report.print_report(p[0], msg); +// ** Convert integer delays in K_THREAD_DEFINE to the appropriate macro + +// Identify declarers where an identifier is used for the delay +@r_thread_decl_id@ +declarer name K_THREAD_DEFINE; +identifier C; +position p; +@@ +K_THREAD_DEFINE@p(..., C); + +// Select declarers with constant literal delay and replace with +// appropriate macro +@depends on patch@ +declarer name K_THREAD_DEFINE; +constant C; +position p != r_thread_decl_id.p; +@@ +K_THREAD_DEFINE@p(..., +( +- 0 ++ K_NO_WAIT +| +- -1 ++ K_FOREVER +| +- C ++ K_MSEC(C) +) + ); + +// Identify declarers where an identifier is used for the delay +@r_thread_decl_const + depends on report@ +declarer name K_THREAD_DEFINE; +constant C; +position p != r_thread_decl_id.p; +@@ +K_THREAD_DEFINE@p(..., C); + + +@script:python + depends on report +@ +C << r_thread_decl_const.C; +p << r_thread_decl_const.p; +@@ +msg = "WARNING: replace constant {} with timeout in K_THREAD_DEFINE".format(C) +coccilib.report.print_report(p[0], msg); + // ** Handle k_timer_start where the second (not last) argument is a // ** constant literal. From ca345690412fe0f27ef459bcaa7423d022b6e365 Mon Sep 17 00:00:00 2001 From: Peter Bigot Date: Sun, 6 Oct 2019 14:59:16 -0500 Subject: [PATCH 6/6] coccinelle: standardize k_thread create/define calls with integer timeouts Re-run with updated script to convert integer literal delay arguments to k_thread_create and K_THREAD_DEFINE to use the standard timeout macros. Signed-off-by: Peter Bigot --- drivers/sensor/adt7420/adt7420_trigger.c | 2 +- drivers/sensor/adxl362/adxl362_trigger.c | 2 +- drivers/sensor/adxl372/adxl372_trigger.c | 2 +- drivers/sensor/amg88xx/amg88xx_trigger.c | 2 +- drivers/sensor/bma280/bma280_trigger.c | 2 +- drivers/sensor/hmc5883l/hmc5883l_trigger.c | 2 +- drivers/sensor/hts221/hts221_trigger.c | 2 +- drivers/sensor/isl29035/isl29035_trigger.c | 2 +- drivers/sensor/lis2ds12/lis2ds12_trigger.c | 2 +- drivers/sensor/lis2mdl/lis2mdl_trigger.c | 2 +- drivers/sensor/lis3mdl/lis3mdl_trigger.c | 2 +- drivers/sensor/lsm6dsl/lsm6dsl_trigger.c | 2 +- drivers/sensor/mpu6050/mpu6050_trigger.c | 2 +- drivers/sensor/sht3xd/sht3xd_trigger.c | 2 +- drivers/sensor/tmp007/tmp007_trigger.c | 2 +- kernel/work_q.c | 2 +- samples/bluetooth/ipsp/src/main.c | 2 +- samples/subsys/ipc/openamp/remote/src/main.c | 2 +- samples/subsys/ipc/openamp/src/main.c | 2 +- samples/subsys/logging/logger/src/main.c | 2 +- subsys/net/ip/net_if.c | 2 +- subsys/net/ip/net_mgmt.c | 3 ++- subsys/net/l2/ethernet/gptp/gptp.c | 2 +- subsys/net/lib/conn_mgr/conn_mgr.c | 2 +- subsys/testsuite/ztest/src/ztest.c | 3 ++- subsys/usb/class/mass_storage.c | 2 +- tests/benchmarks/sched/src/main.c | 2 +- .../timing_info/src/msg_passing_bench.c | 21 ++++++++++--------- .../timing_info/src/semaphore_bench.c | 8 +++---- .../benchmarks/timing_info/src/thread_bench.c | 6 +++--- .../timing_info/src/userspace_bench.c | 8 +++---- .../benchmarks/timing_info/src/yield_bench.c | 4 ++-- tests/drivers/spi/spi_loopback/src/spi.c | 2 +- tests/kernel/common/src/timeout_order.c | 2 +- tests/kernel/context/src/main.c | 10 ++++----- tests/kernel/critical/src/main.c | 4 ++-- tests/kernel/early_sleep/src/main.c | 2 +- .../fifo/fifo_api/src/test_fifo_cancel.c | 2 +- .../fifo/fifo_api/src/test_fifo_contexts.c | 2 +- .../kernel/fifo/fifo_api/src/test_fifo_loop.c | 2 +- tests/kernel/fifo/fifo_timeout/src/main.c | 14 ++++++------- tests/kernel/fifo/fifo_usage/src/main.c | 6 +++--- .../lifo/lifo_api/src/test_lifo_contexts.c | 2 +- .../kernel/lifo/lifo_api/src/test_lifo_loop.c | 2 +- tests/kernel/lifo/lifo_usage/src/main.c | 14 ++++++------- .../kernel/mbox/mbox_api/src/test_mbox_api.c | 2 +- .../src/test_mpool_alloc_wait.c | 6 +++--- .../mem_pool/mem_pool_threadsafe/src/main.c | 2 +- .../mslab_concept/src/test_mslab_alloc_wait.c | 6 +++--- .../src/test_mslab_threadsafe.c | 2 +- .../msgq/msgq_api/src/test_msgq_contexts.c | 8 +++---- .../msgq/msgq_api/src/test_msgq_purge.c | 3 ++- .../mutex/mutex_api/src/test_mutex_apis.c | 4 ++-- tests/kernel/pending/src/main.c | 6 ++++-- tests/kernel/pipe/pipe/src/test_pipe.c | 15 ++++++++----- .../pipe/pipe_api/src/test_pipe_contexts.c | 20 +++++++++--------- tests/kernel/poll/src/test_poll.c | 17 ++++++++------- tests/kernel/queue/src/test_queue_contexts.c | 6 +++--- tests/kernel/queue/src/test_queue_loop.c | 2 +- tests/kernel/queue/src/test_queue_user.c | 2 +- tests/kernel/sched/deadline/src/main.c | 2 +- tests/kernel/sched/preempt/src/main.c | 4 ++-- .../src/test_priority_scheduling.c | 3 ++- .../src/test_sched_is_preempt_thread.c | 4 ++-- .../schedule_api/src/test_sched_priority.c | 6 +++--- .../src/test_sched_timeslice_and_lock.c | 7 ++++--- .../src/test_sched_timeslice_reset.c | 3 ++- .../schedule_api/src/test_slice_scheduling.c | 3 ++- .../kernel/sched/schedule_api/src/user_api.c | 6 +++--- tests/kernel/semaphore/sema_api/src/main.c | 2 +- tests/kernel/sleep/src/main.c | 4 ++-- tests/kernel/spinlock/src/main.c | 2 +- .../stack/stack_api/src/test_stack_contexts.c | 5 +++-- tests/kernel/stack/stack_usage/src/main.c | 6 +++--- .../kernel/threads/dynamic_thread/src/main.c | 4 ++-- tests/kernel/threads/thread_apis/src/main.c | 8 +++---- .../thread_apis/src/test_essential_thread.c | 3 ++- .../thread_apis/src/test_kthread_for_each.c | 2 +- .../src/test_threads_cancel_abort.c | 12 +++++------ .../src/test_threads_set_priority.c | 3 ++- .../thread_apis/src/test_threads_spawn.c | 6 +++--- .../src/test_threads_suspend_resume.c | 2 +- tests/kernel/workq/work_queue/src/main.c | 8 +++---- tests/net/buf/src/main.c | 2 +- tests/net/context/src/main.c | 4 ++-- tests/net/mgmt/src/mgmt.c | 2 +- 86 files changed, 201 insertions(+), 180 deletions(-) diff --git a/drivers/sensor/adt7420/adt7420_trigger.c b/drivers/sensor/adt7420/adt7420_trigger.c index 6f2a670362a34..fcb09ba193b8d 100644 --- a/drivers/sensor/adt7420/adt7420_trigger.c +++ b/drivers/sensor/adt7420/adt7420_trigger.c @@ -130,7 +130,7 @@ int adt7420_init_interrupt(struct device *dev) CONFIG_ADT7420_THREAD_STACK_SIZE, (k_thread_entry_t)adt7420_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_ADT7420_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_ADT7420_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = adt7420_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/adxl362/adxl362_trigger.c b/drivers/sensor/adxl362/adxl362_trigger.c index eb9d5faf0ab61..b3a5329a4417b 100644 --- a/drivers/sensor/adxl362/adxl362_trigger.c +++ b/drivers/sensor/adxl362/adxl362_trigger.c @@ -160,7 +160,7 @@ int adxl362_init_interrupt(struct device *dev) CONFIG_ADXL362_THREAD_STACK_SIZE, (k_thread_entry_t)adxl362_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_ADXL362_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_ADXL362_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = adxl362_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/adxl372/adxl372_trigger.c b/drivers/sensor/adxl372/adxl372_trigger.c index 63bdf1741b9eb..dac2d2725922d 100644 --- a/drivers/sensor/adxl372/adxl372_trigger.c +++ b/drivers/sensor/adxl372/adxl372_trigger.c @@ -165,7 +165,7 @@ int adxl372_init_interrupt(struct device *dev) CONFIG_ADXL372_THREAD_STACK_SIZE, (k_thread_entry_t)adxl372_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_ADXL372_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_ADXL372_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = adxl372_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/amg88xx/amg88xx_trigger.c b/drivers/sensor/amg88xx/amg88xx_trigger.c index b2e32c1a8081b..882662ac902e2 100644 --- a/drivers/sensor/amg88xx/amg88xx_trigger.c +++ b/drivers/sensor/amg88xx/amg88xx_trigger.c @@ -183,7 +183,7 @@ int amg88xx_init_interrupt(struct device *dev) CONFIG_AMG88XX_THREAD_STACK_SIZE, (k_thread_entry_t)amg88xx_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_AMG88XX_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_AMG88XX_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = amg88xx_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/bma280/bma280_trigger.c b/drivers/sensor/bma280/bma280_trigger.c index 33a0a33451d7b..a2bc829bc1a93 100644 --- a/drivers/sensor/bma280/bma280_trigger.c +++ b/drivers/sensor/bma280/bma280_trigger.c @@ -270,7 +270,7 @@ int bma280_init_interrupt(struct device *dev) CONFIG_BMA280_THREAD_STACK_SIZE, (k_thread_entry_t)bma280_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_BMA280_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_BMA280_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = bma280_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/hmc5883l/hmc5883l_trigger.c b/drivers/sensor/hmc5883l/hmc5883l_trigger.c index 19d2ac6c08400..ce829b24e82c4 100644 --- a/drivers/sensor/hmc5883l/hmc5883l_trigger.c +++ b/drivers/sensor/hmc5883l/hmc5883l_trigger.c @@ -126,7 +126,7 @@ int hmc5883l_init_interrupt(struct device *dev) CONFIG_HMC5883L_THREAD_STACK_SIZE, (k_thread_entry_t)hmc5883l_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_HMC5883L_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_HMC5883L_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = hmc5883l_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/hts221/hts221_trigger.c b/drivers/sensor/hts221/hts221_trigger.c index bf70a0ac352b2..7138fe440ed61 100644 --- a/drivers/sensor/hts221/hts221_trigger.c +++ b/drivers/sensor/hts221/hts221_trigger.c @@ -136,7 +136,7 @@ int hts221_init_interrupt(struct device *dev) CONFIG_HTS221_THREAD_STACK_SIZE, (k_thread_entry_t)hts221_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_HTS221_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_HTS221_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = hts221_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/isl29035/isl29035_trigger.c b/drivers/sensor/isl29035/isl29035_trigger.c index 0e747ca0137a1..30e3bbc93a883 100644 --- a/drivers/sensor/isl29035/isl29035_trigger.c +++ b/drivers/sensor/isl29035/isl29035_trigger.c @@ -180,7 +180,7 @@ int isl29035_init_interrupt(struct device *dev) CONFIG_ISL29035_THREAD_STACK_SIZE, (k_thread_entry_t)isl29035_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_ISL29035_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_ISL29035_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = isl29035_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/lis2ds12/lis2ds12_trigger.c b/drivers/sensor/lis2ds12/lis2ds12_trigger.c index c89e13221e372..bd09f7f0c5dd1 100644 --- a/drivers/sensor/lis2ds12/lis2ds12_trigger.c +++ b/drivers/sensor/lis2ds12/lis2ds12_trigger.c @@ -147,7 +147,7 @@ int lis2ds12_trigger_init(struct device *dev) CONFIG_LIS2DS12_THREAD_STACK_SIZE, (k_thread_entry_t)lis2ds12_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_LIS2DS12_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_LIS2DS12_TRIGGER_GLOBAL_THREAD) data->work.handler = lis2ds12_work_cb; data->dev = dev; diff --git a/drivers/sensor/lis2mdl/lis2mdl_trigger.c b/drivers/sensor/lis2mdl/lis2mdl_trigger.c index 5eb96e407c510..9064015a2728e 100644 --- a/drivers/sensor/lis2mdl/lis2mdl_trigger.c +++ b/drivers/sensor/lis2mdl/lis2mdl_trigger.c @@ -129,7 +129,7 @@ int lis2mdl_init_interrupt(struct device *dev) CONFIG_LIS2MDL_THREAD_STACK_SIZE, (k_thread_entry_t)lis2mdl_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_LIS2MDL_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_LIS2MDL_TRIGGER_GLOBAL_THREAD) lis2mdl->work.handler = lis2mdl_work_cb; lis2mdl->dev = dev; diff --git a/drivers/sensor/lis3mdl/lis3mdl_trigger.c b/drivers/sensor/lis3mdl/lis3mdl_trigger.c index 3e63f1a5760e2..772baac09c2fc 100644 --- a/drivers/sensor/lis3mdl/lis3mdl_trigger.c +++ b/drivers/sensor/lis3mdl/lis3mdl_trigger.c @@ -139,7 +139,7 @@ int lis3mdl_init_interrupt(struct device *dev) CONFIG_LIS3MDL_THREAD_STACK_SIZE, (k_thread_entry_t)lis3mdl_thread, POINTER_TO_INT(dev), 0, NULL, K_PRIO_COOP(CONFIG_LIS3MDL_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_LIS3MDL_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = lis3mdl_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/lsm6dsl/lsm6dsl_trigger.c b/drivers/sensor/lsm6dsl/lsm6dsl_trigger.c index c4d28b44fb049..9f3a0a0a7e12a 100644 --- a/drivers/sensor/lsm6dsl/lsm6dsl_trigger.c +++ b/drivers/sensor/lsm6dsl/lsm6dsl_trigger.c @@ -137,7 +137,7 @@ int lsm6dsl_init_interrupt(struct device *dev) CONFIG_LSM6DSL_THREAD_STACK_SIZE, (k_thread_entry_t)lsm6dsl_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_LSM6DSL_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_LSM6DSL_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = lsm6dsl_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/mpu6050/mpu6050_trigger.c b/drivers/sensor/mpu6050/mpu6050_trigger.c index f6e4689d3097d..6d6569496964b 100644 --- a/drivers/sensor/mpu6050/mpu6050_trigger.c +++ b/drivers/sensor/mpu6050/mpu6050_trigger.c @@ -134,7 +134,7 @@ int mpu6050_init_interrupt(struct device *dev) CONFIG_MPU6050_THREAD_STACK_SIZE, (k_thread_entry_t)mpu6050_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_MPU6050_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_MPU6050_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = mpu6050_work_cb; drv_data->dev = dev; diff --git a/drivers/sensor/sht3xd/sht3xd_trigger.c b/drivers/sensor/sht3xd/sht3xd_trigger.c index 6d32f4342d2e5..09c94a605f394 100644 --- a/drivers/sensor/sht3xd/sht3xd_trigger.c +++ b/drivers/sensor/sht3xd/sht3xd_trigger.c @@ -223,7 +223,7 @@ int sht3xd_init_interrupt(struct device *dev) CONFIG_SHT3XD_THREAD_STACK_SIZE, (k_thread_entry_t)sht3xd_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_SHT3XD_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_SHT3XD_TRIGGER_GLOBAL_THREAD) data->work.handler = sht3xd_work_cb; #endif diff --git a/drivers/sensor/tmp007/tmp007_trigger.c b/drivers/sensor/tmp007/tmp007_trigger.c index 7524ca69c8b60..71031a98f286b 100644 --- a/drivers/sensor/tmp007/tmp007_trigger.c +++ b/drivers/sensor/tmp007/tmp007_trigger.c @@ -172,7 +172,7 @@ int tmp007_init_interrupt(struct device *dev) CONFIG_TMP007_THREAD_STACK_SIZE, (k_thread_entry_t)tmp007_thread, dev, 0, NULL, K_PRIO_COOP(CONFIG_TMP007_THREAD_PRIORITY), - 0, 0); + 0, K_NO_WAIT); #elif defined(CONFIG_TMP007_TRIGGER_GLOBAL_THREAD) drv_data->work.handler = tmp007_work_cb; drv_data->dev = dev; diff --git a/kernel/work_q.c b/kernel/work_q.c index 3122477bf2341..f050a437ab818 100644 --- a/kernel/work_q.c +++ b/kernel/work_q.c @@ -30,7 +30,7 @@ void k_work_q_start(struct k_work_q *work_q, k_thread_stack_t *stack, { k_queue_init(&work_q->queue); (void)k_thread_create(&work_q->thread, stack, stack_size, z_work_q_main, - work_q, NULL, NULL, prio, 0, 0); + work_q, NULL, NULL, prio, 0, K_NO_WAIT); k_thread_name_set(&work_q->thread, WORKQUEUE_THREAD_NAME); } diff --git a/samples/bluetooth/ipsp/src/main.c b/samples/bluetooth/ipsp/src/main.c index a05a07b1fa807..1c6c6d8de845d 100644 --- a/samples/bluetooth/ipsp/src/main.c +++ b/samples/bluetooth/ipsp/src/main.c @@ -339,5 +339,5 @@ void main(void) k_thread_create(&thread_data, thread_stack, STACKSIZE, (k_thread_entry_t)listen, - NULL, NULL, NULL, K_PRIO_COOP(7), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(7), 0, K_NO_WAIT); } diff --git a/samples/subsys/ipc/openamp/remote/src/main.c b/samples/subsys/ipc/openamp/remote/src/main.c index 95139a43f83c6..0f24b3f0a460f 100644 --- a/samples/subsys/ipc/openamp/remote/src/main.c +++ b/samples/subsys/ipc/openamp/remote/src/main.c @@ -252,5 +252,5 @@ void main(void) printk("Starting application thread!\n"); k_thread_create(&thread_data, thread_stack, APP_TASK_STACK_SIZE, (k_thread_entry_t)app_task, - NULL, NULL, NULL, K_PRIO_COOP(7), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(7), 0, K_NO_WAIT); } diff --git a/samples/subsys/ipc/openamp/src/main.c b/samples/subsys/ipc/openamp/src/main.c index 1f99347c0c292..ef4699d63c634 100644 --- a/samples/subsys/ipc/openamp/src/main.c +++ b/samples/subsys/ipc/openamp/src/main.c @@ -278,7 +278,7 @@ void main(void) printk("Starting application thread!\n"); k_thread_create(&thread_data, thread_stack, APP_TASK_STACK_SIZE, (k_thread_entry_t)app_task, - NULL, NULL, NULL, K_PRIO_COOP(7), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(7), 0, K_NO_WAIT); } /* Make sure we clear out the status flag very early (before we bringup the diff --git a/samples/subsys/logging/logger/src/main.c b/samples/subsys/logging/logger/src/main.c index 0813aabef19a2..72b9bb3e811dc 100644 --- a/samples/subsys/logging/logger/src/main.c +++ b/samples/subsys/logging/logger/src/main.c @@ -313,4 +313,4 @@ static void log_demo_supervisor(void *p1, void *p2, void *p3) K_THREAD_DEFINE(log_demo_thread_id, STACKSIZE, log_demo_supervisor, NULL, NULL, NULL, - K_LOWEST_APPLICATION_THREAD_PRIO, 0, 1); + K_LOWEST_APPLICATION_THREAD_PRIO, 0, K_MSEC(1)); diff --git a/subsys/net/ip/net_if.c b/subsys/net/ip/net_if.c index 14d7bcdbd221d..fbea02e0e95ba 100644 --- a/subsys/net/ip/net_if.c +++ b/subsys/net/ip/net_if.c @@ -3633,7 +3633,7 @@ void net_if_init(void) k_thread_create(&tx_thread_ts, tx_ts_stack, K_THREAD_STACK_SIZEOF(tx_ts_stack), (k_thread_entry_t)net_tx_ts_thread, - NULL, NULL, NULL, K_PRIO_COOP(1), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(1), 0, K_NO_WAIT); k_thread_name_set(&tx_thread_ts, "tx_tstamp"); #endif /* CONFIG_NET_PKT_TIMESTAMP_THREAD */ diff --git a/subsys/net/ip/net_mgmt.c b/subsys/net/ip/net_mgmt.c index b2847b9e25b58..d2b09188babcc 100644 --- a/subsys/net/ip/net_mgmt.c +++ b/subsys/net/ip/net_mgmt.c @@ -391,7 +391,8 @@ void net_mgmt_event_init(void) k_thread_create(&mgmt_thread_data, mgmt_stack, K_THREAD_STACK_SIZEOF(mgmt_stack), (k_thread_entry_t)mgmt_thread, NULL, NULL, NULL, - K_PRIO_COOP(CONFIG_NET_MGMT_EVENT_THREAD_PRIO), 0, 0); + K_PRIO_COOP(CONFIG_NET_MGMT_EVENT_THREAD_PRIO), 0, + K_NO_WAIT); k_thread_name_set(&mgmt_thread_data, "net_mgmt"); NET_DBG("Net MGMT initialized: queue of %u entries, stack size of %u", diff --git a/subsys/net/l2/ethernet/gptp/gptp.c b/subsys/net/l2/ethernet/gptp/gptp.c index bf2892e50b0a7..06f8c92684dd8 100644 --- a/subsys/net/l2/ethernet/gptp/gptp.c +++ b/subsys/net/l2/ethernet/gptp/gptp.c @@ -908,7 +908,7 @@ static void init_ports(void) tid = k_thread_create(&gptp_thread_data, gptp_stack, K_THREAD_STACK_SIZEOF(gptp_stack), (k_thread_entry_t)gptp_thread, - NULL, NULL, NULL, K_PRIO_COOP(5), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(5), 0, K_NO_WAIT); k_thread_name_set(&gptp_thread_data, "gptp"); } diff --git a/subsys/net/lib/conn_mgr/conn_mgr.c b/subsys/net/lib/conn_mgr/conn_mgr.c index 7d707e7d4f7eb..09989f52fd0f0 100644 --- a/subsys/net/lib/conn_mgr/conn_mgr.c +++ b/subsys/net/lib/conn_mgr/conn_mgr.c @@ -172,7 +172,7 @@ static void conn_mgr(void) K_THREAD_DEFINE(conn_mgr_thread, CONFIG_NET_CONNECTION_MANAGER_STACK_SIZE, (k_thread_entry_t)conn_mgr, NULL, NULL, NULL, - K_PRIO_COOP(2), 0, 0); + K_PRIO_COOP(2), 0, K_NO_WAIT); void net_conn_mgr_resend_status(void) { diff --git a/subsys/testsuite/ztest/src/ztest.c b/subsys/testsuite/ztest/src/ztest.c index 51ddd55bdf4f4..e7775350cf595 100644 --- a/subsys/testsuite/ztest/src/ztest.c +++ b/subsys/testsuite/ztest/src/ztest.c @@ -283,7 +283,8 @@ static int run_test(struct unit_test *test) K_THREAD_STACK_SIZEOF(ztest_thread_stack), (k_thread_entry_t) test_cb, (struct unit_test *)test, NULL, NULL, CONFIG_ZTEST_THREAD_PRIORITY, - test->thread_options | K_INHERIT_PERMS, 0); + test->thread_options | K_INHERIT_PERMS, + K_NO_WAIT); /* * There is an implicit expectation here that the thread that was * spawned is still higher priority than the current thread. diff --git a/subsys/usb/class/mass_storage.c b/subsys/usb/class/mass_storage.c index 96795107cf685..08cdadf3b87fd 100644 --- a/subsys/usb/class/mass_storage.c +++ b/subsys/usb/class/mass_storage.c @@ -955,7 +955,7 @@ static int mass_storage_init(struct device *dev) k_thread_create(&mass_thread_data, mass_thread_stack, DISK_THREAD_STACK_SZ, (k_thread_entry_t)mass_thread_main, NULL, NULL, NULL, - DISK_THREAD_PRIO, 0, 0); + DISK_THREAD_PRIO, 0, K_NO_WAIT); return 0; } diff --git a/tests/benchmarks/sched/src/main.c b/tests/benchmarks/sched/src/main.c index 4f5b3f715d5b1..8bef594feff10 100644 --- a/tests/benchmarks/sched/src/main.c +++ b/tests/benchmarks/sched/src/main.c @@ -105,7 +105,7 @@ void main(void) k_tid_t th = k_thread_create(&partner_thread, partner_stack, K_THREAD_STACK_SIZEOF(partner_stack), partner_fn, NULL, NULL, NULL, - partner_prio, 0, 0); + partner_prio, 0, K_NO_WAIT); /* Let it start running and pend */ k_sleep(K_MSEC(100)); diff --git a/tests/benchmarks/timing_info/src/msg_passing_bench.c b/tests/benchmarks/timing_info/src/msg_passing_bench.c index 9feecac3fb90b..16cbd52170193 100644 --- a/tests/benchmarks/timing_info/src/msg_passing_bench.c +++ b/tests/benchmarks/timing_info/src/msg_passing_bench.c @@ -129,7 +129,7 @@ void msg_passing_bench(void) producer_w_cxt_switch_tid = k_thread_create(&my_thread, my_stack_area, STACK_SIZE, thread_producer_msgq_w_cxt_switch, NULL, - NULL, NULL, 2 /*priority*/, 0, 50); + NULL, NULL, 2 /*priority*/, 0, K_MSEC(50)); u32_t msg_status = k_msgq_get(&benchmark_q, &received_data, K_MSEC(300)); @@ -137,7 +137,8 @@ void msg_passing_bench(void) producer_wo_cxt_switch_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_producer_msgq_wo_cxt_switch, - NULL, NULL, NULL, -2 /*priority*/, 0, 0); + NULL, NULL, NULL, -2 /*priority*/, 0, + K_NO_WAIT); k_thread_abort(producer_w_cxt_switch_tid); k_thread_abort(producer_wo_cxt_switch_tid); @@ -152,13 +153,13 @@ void msg_passing_bench(void) k_thread_create(&my_thread, my_stack_area, STACK_SIZE, thread_producer_get_msgq_w_cxt_switch, NULL, - NULL, NULL, 1 /*priority*/, 0, 50); + NULL, NULL, 1 /*priority*/, 0, K_MSEC(50)); consumer_get_w_cxt_switch_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_consumer_get_msgq_w_cxt_switch, NULL, NULL, NULL, - 2 /*priority*/, 0, 50); + 2 /*priority*/, 0, K_MSEC(50)); k_sleep(K_MSEC(2000)); /* make the main thread sleep */ k_thread_abort(producer_get_w_cxt_switch_tid); __msg_q_get_w_cxt_end_time = (z_arch_timing_value_swap_common); @@ -187,13 +188,13 @@ void msg_passing_bench(void) STACK_SIZE, thread_mbox_sync_put_send, NULL, NULL, NULL, - 2 /*priority*/, 0, 0); + 2 /*priority*/, 0, K_NO_WAIT); thread_mbox_sync_put_receive_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_mbox_sync_put_receive, NULL, NULL, NULL, - 1 /*priority*/, 0, 0); + 1 /*priority*/, 0, K_NO_WAIT); k_sleep(K_MSEC(1000)); /* make the main thread sleep */ mbox_sync_put_end_time = (z_arch_timing_value_swap_common); @@ -206,12 +207,12 @@ void msg_passing_bench(void) STACK_SIZE, thread_mbox_sync_get_send, NULL, NULL, NULL, - 1 /*prio*/, 0, 0); + 1 /*prio*/, 0, K_NO_WAIT); thread_mbox_sync_get_receive_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_mbox_sync_get_receive, NULL, - NULL, NULL, 2 /*priority*/, 0, 0); + NULL, NULL, 2 /*priority*/, 0, K_NO_WAIT); k_sleep(K_MSEC(1000)); /* make the main thread sleep */ mbox_sync_get_end_time = (z_arch_timing_value_swap_common); @@ -224,13 +225,13 @@ void msg_passing_bench(void) STACK_SIZE, thread_mbox_async_put_send, NULL, NULL, NULL, - 2 /*prio*/, 0, 0); + 2 /*prio*/, 0, K_NO_WAIT); thread_mbox_async_put_receive_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_mbox_async_put_receive, NULL, NULL, NULL, - 3 /*priority*/, 0, 0); + 3 /*priority*/, 0, K_NO_WAIT); k_sleep(K_MSEC(1000)); /* make the main thread sleep */ /*******************************************************************/ diff --git a/tests/benchmarks/timing_info/src/semaphore_bench.c b/tests/benchmarks/timing_info/src/semaphore_bench.c index 5dda5a308d6c7..bd108bca4b83b 100644 --- a/tests/benchmarks/timing_info/src/semaphore_bench.c +++ b/tests/benchmarks/timing_info/src/semaphore_bench.c @@ -54,11 +54,11 @@ void semaphore_bench(void) sem0_tid = k_thread_create(&my_thread, my_stack_area, STACK_SIZE, thread_sem0_test, NULL, NULL, NULL, - 2 /*priority*/, 0, 0); + 2 /*priority*/, 0, K_NO_WAIT); sem1_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_sem1_test, NULL, NULL, NULL, - 2 /*priority*/, 0, 0); + 2 /*priority*/, 0, K_NO_WAIT); k_sleep(K_MSEC(1000)); @@ -70,11 +70,11 @@ void semaphore_bench(void) sem0_tid = k_thread_create(&my_thread, my_stack_area, STACK_SIZE, thread_sem0_give_test, NULL, NULL, NULL, - 2 /*priority*/, 0, 0); + 2 /*priority*/, 0, K_NO_WAIT); sem1_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_sem1_give_test, NULL, NULL, NULL, - 2 /*priority*/, 0, 0); + 2 /*priority*/, 0, K_NO_WAIT); k_sleep(K_MSEC(1000)); sem_give_end_time = (z_arch_timing_value_swap_common); diff --git a/tests/benchmarks/timing_info/src/thread_bench.c b/tests/benchmarks/timing_info/src/thread_bench.c index af5fbb2cbaca3..65a219fd35a83 100644 --- a/tests/benchmarks/timing_info/src/thread_bench.c +++ b/tests/benchmarks/timing_info/src/thread_bench.c @@ -139,7 +139,7 @@ void system_thread_bench(void) k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_swap_test, NULL, NULL, NULL, - -1 /*priority*/, 0, 0); + -1 /*priority*/, 0, K_NO_WAIT); k_sleep(K_MSEC(1)); thread_abort_end_time = (z_arch_timing_value_swap_common); @@ -166,7 +166,7 @@ void system_thread_bench(void) STACK_SIZE, thread_swap_test, NULL, NULL, NULL, - 5 /*priority*/, 0, 10); + 5 /*priority*/, 0, K_MSEC(10)); TIMING_INFO_PRE_READ(); thread_create_end_time = TIMING_INFO_OS_GET_TIME(); @@ -183,7 +183,7 @@ void system_thread_bench(void) STACK_SIZE, thread_suspend_test, NULL, NULL, NULL, - -1 /*priority*/, 0, 0); + -1 /*priority*/, 0, K_NO_WAIT); TIMING_INFO_PRE_READ(); thread_suspend_end_time = TIMING_INFO_OS_GET_TIME(); diff --git a/tests/benchmarks/timing_info/src/userspace_bench.c b/tests/benchmarks/timing_info/src/userspace_bench.c index 687ca0bd62e42..8431678b54572 100644 --- a/tests/benchmarks/timing_info/src/userspace_bench.c +++ b/tests/benchmarks/timing_info/src/userspace_bench.c @@ -100,7 +100,7 @@ void drop_to_user_mode(void) k_thread_create(&my_thread_user, my_stack_area_0, STACK_SIZE, drop_to_user_mode_thread, NULL, NULL, NULL, - -1 /*priority*/, K_INHERIT_PERMS, 0); + -1 /*priority*/, K_INHERIT_PERMS, K_NO_WAIT); k_yield(); @@ -135,7 +135,7 @@ void user_thread_creation(void) k_thread_create(&my_thread_user, my_stack_area, STACK_SIZE, test_drop_to_user_mode_1, NULL, NULL, NULL, - 0 /*priority*/, K_INHERIT_PERMS | K_USER, 0); + 0 /*priority*/, K_INHERIT_PERMS | K_USER, K_NO_WAIT); TIMING_INFO_PRE_READ(); user_thread_creation_end_time = TIMING_INFO_GET_TIMER_VALUE(); @@ -189,7 +189,7 @@ void syscall_overhead(void) k_thread_create(&my_thread_user, my_stack_area_0, STACK_SIZE, syscall_overhead_user_thread, NULL, NULL, NULL, - -1 /*priority*/, K_INHERIT_PERMS | K_USER, 0); + -1 /*priority*/, K_INHERIT_PERMS | K_USER, K_NO_WAIT); u32_t total_cycles = (u32_t) @@ -253,7 +253,7 @@ void validation_overhead(void) k_thread_create(&my_thread_user, my_stack_area, STACK_SIZE, validation_overhead_user_thread, NULL, NULL, NULL, - -1 /*priority*/, K_INHERIT_PERMS | K_USER, 0); + -1 /*priority*/, K_INHERIT_PERMS | K_USER, K_NO_WAIT); u32_t total_cycles_obj_init = (u32_t) diff --git a/tests/benchmarks/timing_info/src/yield_bench.c b/tests/benchmarks/timing_info/src/yield_bench.c index b6b3852b90ee8..127a5c6401498 100644 --- a/tests/benchmarks/timing_info/src/yield_bench.c +++ b/tests/benchmarks/timing_info/src/yield_bench.c @@ -39,13 +39,13 @@ void yield_bench(void) STACK_SIZE, thread_yield0_test, NULL, NULL, NULL, - 0 /*priority*/, 0, 0); + 0 /*priority*/, 0, K_NO_WAIT); yield1_tid = k_thread_create(&my_thread_0, my_stack_area_0, STACK_SIZE, thread_yield1_test, NULL, NULL, NULL, - 0 /*priority*/, 0, 0); + 0 /*priority*/, 0, K_NO_WAIT); /*read the time of start of the sleep till the swap happens */ z_arch_timing_value_swap_end = 1U; diff --git a/tests/drivers/spi/spi_loopback/src/spi.c b/tests/drivers/spi/spi_loopback/src/spi.c index 887d4df308119..1e60e8809ca0e 100644 --- a/tests/drivers/spi/spi_loopback/src/spi.c +++ b/tests/drivers/spi/spi_loopback/src/spi.c @@ -445,7 +445,7 @@ void testing_spi(void) spi_async_stack, STACK_SIZE, (k_thread_entry_t)spi_async_call_cb, &async_evt, &caller, NULL, - K_PRIO_COOP(7), 0, 0); + K_PRIO_COOP(7), 0, K_NO_WAIT); if (spi_complete_loop(spi_slow, &spi_cfg_slow) || spi_rx_half_start(spi_slow, &spi_cfg_slow) || diff --git a/tests/kernel/common/src/timeout_order.c b/tests/kernel/common/src/timeout_order.c index 7d47d16f90b7d..d5f4f36283552 100644 --- a/tests/kernel/common/src/timeout_order.c +++ b/tests/kernel/common/src/timeout_order.c @@ -56,7 +56,7 @@ void test_timeout_order(void) for (ii = 0; ii < NUM_TIMEOUTS; ii++) { (void)k_thread_create(&threads[ii], stacks[ii], STACKSIZE, thread, INT_TO_POINTER(ii), 0, 0, - prio, 0, 0); + prio, 0, K_NO_WAIT); k_timer_init(&timer[ii], 0, 0); k_sem_init(&sem[ii], 0, 1); results[ii] = -1; diff --git a/tests/kernel/context/src/main.c b/tests/kernel/context/src/main.c index f76da596894f7..b35802f00db0f 100644 --- a/tests/kernel/context/src/main.c +++ b/tests/kernel/context/src/main.c @@ -579,7 +579,7 @@ static void k_yield_entry(void *arg0, void *arg1, void *arg2) k_thread_create(&thread_data2, thread_stack2, THREAD_STACKSIZE, thread_helper, NULL, NULL, NULL, - K_PRIO_COOP(THREAD_PRIORITY - 1), 0, 0); + K_PRIO_COOP(THREAD_PRIORITY - 1), 0, K_NO_WAIT); zassert_equal(thread_evidence, 0, "Helper created at higher priority ran prematurely."); @@ -740,7 +740,7 @@ static void test_busy_wait(void) k_thread_create(&timeout_threads[0], timeout_stacks[0], THREAD_STACKSIZE2, busy_wait_thread, INT_TO_POINTER(timeout), NULL, - NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, 0); + NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, K_NO_WAIT); rv = k_sem_take(&reply_timeout, timeout * 2); @@ -767,7 +767,7 @@ static void test_k_sleep(void) k_thread_create(&timeout_threads[0], timeout_stacks[0], THREAD_STACKSIZE2, thread_sleep, INT_TO_POINTER(timeout), NULL, - NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, 0); + NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, K_NO_WAIT); rv = k_sem_take(&reply_timeout, timeout * 2); zassert_equal(rv, 0, " *** thread timed out waiting for thread on " @@ -888,7 +888,7 @@ void test_k_yield(void) k_thread_create(&thread_data1, thread_stack1, THREAD_STACKSIZE, k_yield_entry, NULL, NULL, - NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, 0); + NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, K_NO_WAIT); zassert_equal(thread_evidence, 1, "Thread did not execute as expected!: %d", thread_evidence); @@ -910,7 +910,7 @@ void test_kernel_thread(void) k_thread_create(&thread_data3, thread_stack3, THREAD_STACKSIZE, kernel_thread_entry, NULL, NULL, - NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, 0); + NULL, K_PRIO_COOP(THREAD_PRIORITY), 0, K_NO_WAIT); } diff --git a/tests/kernel/critical/src/main.c b/tests/kernel/critical/src/main.c index 3fa7ffcacb2a5..02cf4c5d8361a 100644 --- a/tests/kernel/critical/src/main.c +++ b/tests/kernel/critical/src/main.c @@ -196,11 +196,11 @@ static void start_threads(void) { k_thread_create(&thread1, stack1, STACK_SIZE, alternate_thread, NULL, NULL, NULL, - K_PRIO_PREEMPT(12), 0, 0); + K_PRIO_PREEMPT(12), 0, K_NO_WAIT); k_thread_create(&thread2, stack2, STACK_SIZE, regression_thread, NULL, NULL, NULL, - K_PRIO_PREEMPT(12), 0, 0); + K_PRIO_PREEMPT(12), 0, K_NO_WAIT); } /** diff --git a/tests/kernel/early_sleep/src/main.c b/tests/kernel/early_sleep/src/main.c index c44a72a5d4890..7db8befb773ac 100644 --- a/tests/kernel/early_sleep/src/main.c +++ b/tests/kernel/early_sleep/src/main.c @@ -112,7 +112,7 @@ static void test_early_sleep(void) helper_tstack, THREAD_STACK, helper_thread, NULL, NULL, NULL, k_thread_priority_get(k_current_get()) + 1, - K_INHERIT_PERMS, 0); + K_INHERIT_PERMS, K_NO_WAIT); TC_PRINT("k_sleep() ticks at POST_KERNEL level: %d\n", actual_post_kernel_sleep_ticks); diff --git a/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c b/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c index d743c43d346e6..4fb3603d14c4b 100644 --- a/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c +++ b/tests/kernel/fifo/fifo_api/src/test_fifo_cancel.c @@ -26,7 +26,7 @@ static void tfifo_thread_thread(struct k_fifo *pfifo) { k_tid_t tid = k_thread_create(&thread, tstack, STACK_SIZE, t_cancel_wait_entry, pfifo, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); u32_t start_t = k_uptime_get_32(); void *ret = k_fifo_get(pfifo, 500); u32_t dur = k_uptime_get_32() - start_t; diff --git a/tests/kernel/fifo/fifo_api/src/test_fifo_contexts.c b/tests/kernel/fifo/fifo_api/src/test_fifo_contexts.c index 44d1419b60a8c..e87eefafb9671 100644 --- a/tests/kernel/fifo/fifo_api/src/test_fifo_contexts.c +++ b/tests/kernel/fifo/fifo_api/src/test_fifo_contexts.c @@ -90,7 +90,7 @@ static void tfifo_thread_thread(struct k_fifo *pfifo) /**TESTPOINT: thread-thread data passing via fifo*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, pfifo, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); tfifo_put(pfifo); k_sem_take(&end_sema, K_FOREVER); k_thread_abort(tid); diff --git a/tests/kernel/fifo/fifo_api/src/test_fifo_loop.c b/tests/kernel/fifo/fifo_api/src/test_fifo_loop.c index 85af447299363..d0e09980f5cc8 100644 --- a/tests/kernel/fifo/fifo_api/src/test_fifo_loop.c +++ b/tests/kernel/fifo/fifo_api/src/test_fifo_loop.c @@ -62,7 +62,7 @@ static void tfifo_read_write(struct k_fifo *pfifo) /**TESTPOINT: thread-isr-thread data passing via fifo*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, pfifo, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); TC_PRINT("main fifo put ---> "); tfifo_put(pfifo); diff --git a/tests/kernel/fifo/fifo_timeout/src/main.c b/tests/kernel/fifo/fifo_timeout/src/main.c index c7bb011ca0f44..8b6b38811d567 100644 --- a/tests/kernel/fifo/fifo_timeout/src/main.c +++ b/tests/kernel/fifo/fifo_timeout/src/main.c @@ -144,7 +144,7 @@ static int test_multiple_threads_pending(struct timeout_order_data *test_data, tid[ii] = k_thread_create(&ttdata[ii], ttstack[ii], TSTACK_SIZE, test_thread_pend_and_timeout, &test_data[ii], NULL, NULL, - FIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + FIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); } /* In general, there is no guarantee of wakeup order when multiple @@ -218,13 +218,13 @@ static int test_multiple_threads_get_data(struct timeout_order_data *test_data, tid[ii] = k_thread_create(&ttdata[ii], ttstack[ii], TSTACK_SIZE, test_thread_pend_and_get_data, &test_data[ii], NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS, K_NO_WAIT); } tid[ii] = k_thread_create(&ttdata[ii], ttstack[ii], TSTACK_SIZE, test_thread_pend_and_timeout, &test_data[ii], NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS, K_NO_WAIT); for (ii = 0; ii < test_data_size-1; ii++) { k_fifo_put(test_data[ii].fifo, get_scratch_packet()); @@ -365,7 +365,7 @@ static void test_timeout_fifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_put_timeout, &fifo_timeout[0], &timeout, NULL, - FIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + FIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); packet = k_fifo_get(&fifo_timeout[0], timeout + 10); zassert_true(packet != NULL, NULL); @@ -381,7 +381,7 @@ static void test_timeout_fifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_timeout_reply_values, &reply_packet, NULL, NULL, - FIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + FIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); k_yield(); packet = k_fifo_get(&timeout_order_fifo, K_NO_WAIT); @@ -400,7 +400,7 @@ static void test_timeout_fifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_timeout_reply_values, &reply_packet, NULL, NULL, - FIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + FIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); k_yield(); packet = k_fifo_get(&timeout_order_fifo, K_NO_WAIT); @@ -420,7 +420,7 @@ static void test_timeout_fifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_timeout_reply_values_wfe, &reply_packet, NULL, NULL, - FIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + FIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); packet = k_fifo_get(&timeout_order_fifo, K_FOREVER); zassert_true(packet != NULL, NULL); diff --git a/tests/kernel/fifo/fifo_usage/src/main.c b/tests/kernel/fifo/fifo_usage/src/main.c index 8b0d3d31a8159..fed48b64d2838 100644 --- a/tests/kernel/fifo/fifo_usage/src/main.c +++ b/tests/kernel/fifo/fifo_usage/src/main.c @@ -156,7 +156,7 @@ static void test_single_fifo_play(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_fn_single, &fifo1, NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS, K_NO_WAIT); /* Let the child thread run */ k_sem_take(&end_sema, K_FOREVER); @@ -187,7 +187,7 @@ static void test_dual_fifo_play(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_fn_dual, &fifo1, &fifo2, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS, K_NO_WAIT); for (i = 0U; i < LIST_LEN; i++) { /* Put item into fifo */ @@ -219,7 +219,7 @@ static void test_isr_fifo_play(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_fn_isr, &fifo1, &fifo2, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS, K_NO_WAIT); /* Put item into fifo */ diff --git a/tests/kernel/lifo/lifo_api/src/test_lifo_contexts.c b/tests/kernel/lifo/lifo_api/src/test_lifo_contexts.c index 1eae1d202b9b1..9bad4cf120dfe 100644 --- a/tests/kernel/lifo/lifo_api/src/test_lifo_contexts.c +++ b/tests/kernel/lifo/lifo_api/src/test_lifo_contexts.c @@ -61,7 +61,7 @@ static void tlifo_thread_thread(struct k_lifo *plifo) /**TESTPOINT: thread-thread data passing via lifo*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, plifo, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); tlifo_put(plifo); k_sem_take(&end_sema, K_FOREVER); k_thread_abort(tid); diff --git a/tests/kernel/lifo/lifo_api/src/test_lifo_loop.c b/tests/kernel/lifo/lifo_api/src/test_lifo_loop.c index 47c340ecf9c9a..229deff048125 100644 --- a/tests/kernel/lifo/lifo_api/src/test_lifo_loop.c +++ b/tests/kernel/lifo/lifo_api/src/test_lifo_loop.c @@ -62,7 +62,7 @@ static void tlifo_read_write(struct k_lifo *plifo) /**TESTPOINT: thread-isr-thread data passing via lifo*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, plifo, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); TC_PRINT("main lifo put ---> "); tlifo_put(plifo); diff --git a/tests/kernel/lifo/lifo_usage/src/main.c b/tests/kernel/lifo/lifo_usage/src/main.c index ac685e3be70c2..a2c354dbfcc5b 100644 --- a/tests/kernel/lifo/lifo_usage/src/main.c +++ b/tests/kernel/lifo/lifo_usage/src/main.c @@ -125,7 +125,7 @@ static int test_multiple_threads_pending(struct timeout_order_data *test_data, tid[ii] = k_thread_create(&ttdata[ii], ttstack[ii], TSTACK_SIZE, test_thread_pend_and_timeout, &test_data[ii], NULL, NULL, - LIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + LIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); } for (ii = 0; ii < test_data_size; ii++) { @@ -218,7 +218,7 @@ static void test_lifo_nowait(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_nowait, &lifo, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_lifo_put(&lifo, (void *)&data[1]); @@ -240,7 +240,7 @@ static void test_lifo_wait(void) k_tid_t tid = k_thread_create(&tdata1, tstack1, STACK_SIZE, thread_entry_wait, &plifo, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); ret = k_lifo_get(&plifo, K_FOREVER); @@ -322,7 +322,7 @@ static void test_timeout_lifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_put_timeout, &lifo_timeout[0], &timeout, NULL, - LIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + LIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); packet = k_lifo_get(&lifo_timeout[0], timeout + 10); zassert_true(packet != NULL, NULL); @@ -338,7 +338,7 @@ static void test_timeout_lifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_timeout_reply_values, &reply_packet, NULL, NULL, - LIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + LIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); k_yield(); packet = k_lifo_get(&timeout_order_lifo, K_NO_WAIT); @@ -357,7 +357,7 @@ static void test_timeout_lifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_timeout_reply_values, &reply_packet, NULL, NULL, - LIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + LIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); k_yield(); packet = k_lifo_get(&timeout_order_lifo, K_NO_WAIT); @@ -377,7 +377,7 @@ static void test_timeout_lifo_thread(void) tid[0] = k_thread_create(&ttdata[0], ttstack[0], TSTACK_SIZE, test_thread_timeout_reply_values_wfe, &reply_packet, NULL, NULL, - LIFO_THREAD_PRIO, K_INHERIT_PERMS, 0); + LIFO_THREAD_PRIO, K_INHERIT_PERMS, K_NO_WAIT); packet = k_lifo_get(&timeout_order_lifo, K_FOREVER); zassert_true(packet != NULL, NULL); diff --git a/tests/kernel/mbox/mbox_api/src/test_mbox_api.c b/tests/kernel/mbox/mbox_api/src/test_mbox_api.c index d7224b9284862..2d58c9e04b1e6 100644 --- a/tests/kernel/mbox/mbox_api/src/test_mbox_api.c +++ b/tests/kernel/mbox/mbox_api/src/test_mbox_api.c @@ -538,7 +538,7 @@ static void tmbox(struct k_mbox *pmbox) sender_tid = k_current_get(); receiver_tid = k_thread_create(&tdata, tstack, STACK_SIZE, tmbox_entry, pmbox, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); tmbox_put(pmbox); k_sem_take(&end_sema, K_FOREVER); diff --git a/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c b/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c index 032170b0e8d38..0427d74e17c57 100644 --- a/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c +++ b/tests/kernel/mem_pool/mem_pool_concept/src/test_mpool_alloc_wait.c @@ -70,15 +70,15 @@ void test_mpool_alloc_wait_prio(void) /*the low-priority thread*/ tid[0] = k_thread_create(&tdata[0], tstack[0], STACK_SIZE, tmpool_alloc_wait_timeout, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), 0, 0); + K_PRIO_PREEMPT(1), 0, K_NO_WAIT); /*the highest-priority thread that has waited the longest*/ tid[1] = k_thread_create(&tdata[1], tstack[1], STACK_SIZE, tmpool_alloc_wait_ok, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 10); + K_PRIO_PREEMPT(0), 0, K_MSEC(10)); /*the highest-priority thread that has waited shorter*/ tid[2] = k_thread_create(&tdata[2], tstack[2], STACK_SIZE, tmpool_alloc_wait_timeout, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 20); + K_PRIO_PREEMPT(0), 0, K_MSEC(20)); /*relinquish CPU for above threads to start */ k_sleep(K_MSEC(30)); /*free one block, expected to unblock thread "tid[1]"*/ diff --git a/tests/kernel/mem_pool/mem_pool_threadsafe/src/main.c b/tests/kernel/mem_pool/mem_pool_threadsafe/src/main.c index 0b5bbbc697bd6..c85f6b0658a84 100644 --- a/tests/kernel/mem_pool/mem_pool_threadsafe/src/main.c +++ b/tests/kernel/mem_pool/mem_pool_threadsafe/src/main.c @@ -74,7 +74,7 @@ void test_mpool_threadsafe(void) for (int i = 0; i < THREAD_NUM; i++) { tid[i] = k_thread_create(&tdata[i], tstack[i], STACK_SIZE, tmpool_api, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), 0, 0); + K_PRIO_PREEMPT(1), 0, K_NO_WAIT); } /* TESTPOINT: all threads complete and exit the entry function*/ for (int i = 0; i < THREAD_NUM; i++) { diff --git a/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c b/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c index 90e5034faa759..87c0c7162ae01 100644 --- a/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c +++ b/tests/kernel/mem_slab/mslab_concept/src/test_mslab_alloc_wait.c @@ -72,15 +72,15 @@ void test_mslab_alloc_wait_prio(void) /*the low-priority thread*/ tid[0] = k_thread_create(&tdata[0], tstack[0], STACK_SIZE, tmslab_alloc_wait_timeout, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), 0, 0); + K_PRIO_PREEMPT(1), 0, K_NO_WAIT); /*the highest-priority thread that has waited the longest*/ tid[1] = k_thread_create(&tdata[1], tstack[1], STACK_SIZE, tmslab_alloc_wait_ok, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 10); + K_PRIO_PREEMPT(0), 0, K_MSEC(10)); /*the highest-priority thread that has waited shorter*/ tid[2] = k_thread_create(&tdata[2], tstack[2], STACK_SIZE, tmslab_alloc_wait_timeout, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 20); + K_PRIO_PREEMPT(0), 0, K_MSEC(20)); /*relinquish CPU for above threads to start */ k_sleep(K_MSEC(30)); /*free one block, expected to unblock thread "tid[1]"*/ diff --git a/tests/kernel/mem_slab/mslab_threadsafe/src/test_mslab_threadsafe.c b/tests/kernel/mem_slab/mslab_threadsafe/src/test_mslab_threadsafe.c index 2145413d689a8..e748c12b161d9 100644 --- a/tests/kernel/mem_slab/mslab_threadsafe/src/test_mslab_threadsafe.c +++ b/tests/kernel/mem_slab/mslab_threadsafe/src/test_mslab_threadsafe.c @@ -81,7 +81,7 @@ void test_mslab_threadsafe(void) for (int i = 0; i < THREAD_NUM; i++) { tid[i] = k_thread_create(&tdata[i], tstack[i], STACK_SIZE, tmslab_api, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), 0, 0); + K_PRIO_PREEMPT(1), 0, K_NO_WAIT); } /* TESTPOINT: all threads complete and exit the entry function*/ for (int i = 0; i < THREAD_NUM; i++) { diff --git a/tests/kernel/msgq/msgq_api/src/test_msgq_contexts.c b/tests/kernel/msgq/msgq_api/src/test_msgq_contexts.c index 8362e1d6f61a4..2f4a341382d7c 100644 --- a/tests/kernel/msgq/msgq_api/src/test_msgq_contexts.c +++ b/tests/kernel/msgq/msgq_api/src/test_msgq_contexts.c @@ -96,7 +96,7 @@ static void msgq_thread(struct k_msgq *pmsgq) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, pmsgq, NULL, NULL, K_PRIO_PREEMPT(0), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); put_msgq(pmsgq); k_sem_take(&end_sema, K_FOREVER); k_thread_abort(tid); @@ -134,7 +134,7 @@ static void msgq_thread_overflow(struct k_msgq *pmsgq) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_overflow, pmsgq, NULL, NULL, K_PRIO_PREEMPT(0), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); ret = k_msgq_put(pmsgq, (void *)&data[1], K_FOREVER); @@ -184,11 +184,11 @@ static void msgq_thread_data_passing(struct k_msgq *pmsgq) k_tid_t tid = k_thread_create(&tdata2, tstack2, STACK_SIZE, pend_thread_entry, pmsgq, NULL, - NULL, K_PRIO_PREEMPT(0), 0, 0); + NULL, K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_tid_t tid1 = k_thread_create(&tdata1, tstack1, STACK_SIZE, thread_entry_get_data, pmsgq, NULL, - NULL, K_PRIO_PREEMPT(1), 0, 0); + NULL, K_PRIO_PREEMPT(1), 0, K_NO_WAIT); k_sem_take(&end_sema, K_FOREVER); k_thread_abort(tid); diff --git a/tests/kernel/msgq/msgq_api/src/test_msgq_purge.c b/tests/kernel/msgq/msgq_api/src/test_msgq_purge.c index 6de6bfc4f450f..2cb0cd836c122 100644 --- a/tests/kernel/msgq/msgq_api/src/test_msgq_purge.c +++ b/tests/kernel/msgq/msgq_api/src/test_msgq_purge.c @@ -31,7 +31,8 @@ static void purge_when_put(struct k_msgq *q) /*create another thread waiting to put msg*/ k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, q, NULL, NULL, - K_PRIO_PREEMPT(0), K_USER | K_INHERIT_PERMS, 0); + K_PRIO_PREEMPT(0), K_USER | K_INHERIT_PERMS, + K_NO_WAIT); k_sleep(TIMEOUT >> 1); /**TESTPOINT: msgq purge while another thread waiting to put msg*/ k_msgq_purge(q); diff --git a/tests/kernel/mutex/mutex_api/src/test_mutex_apis.c b/tests/kernel/mutex/mutex_api/src/test_mutex_apis.c index f344995b46a00..9d5a565a90967 100644 --- a/tests/kernel/mutex/mutex_api/src/test_mutex_apis.c +++ b/tests/kernel/mutex/mutex_api/src/test_mutex_apis.c @@ -48,7 +48,7 @@ static void tmutex_test_lock(struct k_mutex *pmutex, k_thread_create(&tdata, tstack, STACK_SIZE, entry_fn, pmutex, NULL, NULL, K_PRIO_PREEMPT(0), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); k_mutex_lock(pmutex, K_FOREVER); TC_PRINT("access resource from main thread\n"); @@ -64,7 +64,7 @@ static void tmutex_test_lock_timeout(struct k_mutex *pmutex, k_thread_create(&tdata, tstack, STACK_SIZE, entry_fn, pmutex, NULL, NULL, K_PRIO_PREEMPT(0), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); k_mutex_lock(pmutex, K_FOREVER); TC_PRINT("access resource from main thread\n"); diff --git a/tests/kernel/pending/src/main.c b/tests/kernel/pending/src/main.c index 26562f4e70e9e..e0b002b5ce4f3 100644 --- a/tests/kernel/pending/src/main.c +++ b/tests/kernel/pending/src/main.c @@ -249,10 +249,12 @@ void task_high(void) counter = SEM_TEST_START; k_thread_create(&coop_thread[0], coop_stack[0], COOP_STACKSIZE, - coop_high, NULL, NULL, NULL, K_PRIO_COOP(3), 0, 0); + coop_high, NULL, NULL, NULL, K_PRIO_COOP(3), 0, + K_NO_WAIT); k_thread_create(&coop_thread[1], coop_stack[1], COOP_STACKSIZE, - coop_low, NULL, NULL, NULL, K_PRIO_COOP(7), 0, 0); + coop_low, NULL, NULL, NULL, K_PRIO_COOP(7), 0, + K_NO_WAIT); counter = FIFO_TEST_START; fifo_tests(THIRD_SECOND, &task_high_state, my_fifo_get, k_sem_take); diff --git a/tests/kernel/pipe/pipe/src/test_pipe.c b/tests/kernel/pipe/pipe/src/test_pipe.c index 542d1e5d491b9..76fc2d7d8a94d 100644 --- a/tests/kernel/pipe/pipe/src/test_pipe.c +++ b/tests/kernel/pipe/pipe/src/test_pipe.c @@ -701,7 +701,8 @@ void test_pipe_on_single_elements(void) k_thread_create(&get_single_tid, stack_1, STACK_SIZE, pipe_get_single, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, + K_NO_WAIT); pipe_put_single(); k_sem_take(&sync_sem, K_FOREVER); @@ -718,7 +719,8 @@ void test_pipe_on_multiple_elements(void) { k_thread_create(&get_single_tid, stack_1, STACK_SIZE, pipe_get_multiple, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, + K_NO_WAIT); pipe_put_multiple(); k_sem_take(&sync_sem, K_FOREVER); @@ -735,7 +737,8 @@ void test_pipe_forever_wait(void) { k_thread_create(&get_single_tid, stack_1, STACK_SIZE, pipe_get_forever_wait, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, + K_NO_WAIT); pipe_put_forever_wait(); k_sem_take(&sync_sem, K_FOREVER); @@ -752,7 +755,8 @@ void test_pipe_timeout(void) { k_thread_create(&get_single_tid, stack_1, STACK_SIZE, pipe_get_timeout, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, + K_NO_WAIT); pipe_put_timeout(); k_sem_take(&sync_sem, K_FOREVER); @@ -784,7 +788,8 @@ void test_pipe_forever_timeout(void) k_thread_create(&get_single_tid, stack_1, STACK_SIZE, pipe_get_forever_timeout, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, 0); + K_PRIO_PREEMPT(0), K_INHERIT_PERMS | K_USER, + K_NO_WAIT); pipe_put_forever_timeout(); k_sem_take(&sync_sem, K_FOREVER); diff --git a/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c b/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c index fa1df8cb22a44..06ff46f8488da 100644 --- a/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c +++ b/tests/kernel/pipe/pipe_api/src/test_pipe_contexts.c @@ -106,7 +106,7 @@ static void tpipe_thread_thread(struct k_pipe *ppipe) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, ppipe, NULL, NULL, K_PRIO_PREEMPT(0), - K_INHERIT_PERMS | K_USER, 0); + K_INHERIT_PERMS | K_USER, K_NO_WAIT); tpipe_put(ppipe, K_NO_WAIT); k_sem_take(&end_sema, K_FOREVER); @@ -123,7 +123,7 @@ static void tpipe_kthread_to_kthread(struct k_pipe *ppipe) /**TESTPOINT: thread-thread data passing via pipe*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, ppipe, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); tpipe_put(ppipe, K_NO_WAIT); k_sem_take(&end_sema, K_FOREVER); @@ -210,7 +210,7 @@ void test_pipe_block_put(void) /**TESTPOINT: test k_pipe_block_put without semaphore*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_block_put, &kpipe, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_sleep(K_MSEC(10)); tpipe_get(&kpipe, K_FOREVER); @@ -231,7 +231,7 @@ void test_pipe_block_put_sema(void) /**TESTPOINT: test k_pipe_block_put with semaphore*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_block_put, &pipe, &sync_sema, - NULL, K_PRIO_PREEMPT(0), 0, 0); + NULL, K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_sleep(K_MSEC(10)); tpipe_get(&pipe, K_FOREVER); k_sem_take(&end_sema, K_FOREVER); @@ -248,7 +248,7 @@ void test_pipe_get_put(void) /**TESTPOINT: test API sequence: [get, put]*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_block_put, &kpipe, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); /*get will be executed previous to put*/ tpipe_get(&kpipe, K_FOREVER); @@ -291,7 +291,7 @@ void test_half_pipe_get_put(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_half_pipe_put, &khalfpipe, NULL, NULL, K_PRIO_PREEMPT(0), - K_INHERIT_PERMS | K_USER, 0); + K_INHERIT_PERMS | K_USER, K_NO_WAIT); tpipe_get(&khalfpipe, K_FOREVER); @@ -313,7 +313,7 @@ void test_half_pipe_block_put_sema(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_half_pipe_block_put, &khalfpipe, &sync_sema, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_sleep(K_MSEC(10)); tpipe_get(&khalfpipe, K_FOREVER); @@ -352,7 +352,7 @@ void test_pipe_reader_wait(void) /**TESTPOINT: test k_pipe_block_put with semaphore*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_handler, &kpipe1, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); tpipe_get(&kpipe1, K_FOREVER); k_sem_take(&end_sema, K_FOREVER); @@ -381,12 +381,12 @@ void test_pipe_block_writer_wait(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_for_block_put, &kpipe1, &s_sema, NULL, K_PRIO_PREEMPT(main_low_prio - 1), - 0, 0); + 0, K_NO_WAIT); k_tid_t tid1 = k_thread_create(&tdata1, tstack1, STACK_SIZE, thread_for_block_put, &kpipe1, &s_sema1, NULL, K_PRIO_PREEMPT(main_low_prio - 1), - 0, 0); + 0, K_NO_WAIT); tpipe_get(&kpipe1, K_FOREVER); k_thread_priority_set(k_current_get(), old_prio); diff --git a/tests/kernel/poll/src/test_poll.c b/tests/kernel/poll/src/test_poll.c index 680787a81a42d..161c02b334f5c 100644 --- a/tests/kernel/poll/src/test_poll.c +++ b/tests/kernel/poll/src/test_poll.c @@ -210,7 +210,8 @@ void test_poll_wait(void) k_thread_create(&test_thread, test_stack, K_THREAD_STACK_SIZEOF(test_stack), poll_wait_helper, (void *)1, 0, 0, - main_low_prio - 1, K_USER | K_INHERIT_PERMS, 0); + main_low_prio - 1, K_USER | K_INHERIT_PERMS, + K_NO_WAIT); rc = k_poll(wait_events, ARRAY_SIZE(wait_events), K_SECONDS(1)); @@ -266,7 +267,7 @@ void test_poll_wait(void) k_thread_create(&test_thread, test_stack, K_THREAD_STACK_SIZEOF(test_stack), poll_wait_helper, - 0, 0, 0, main_low_prio - 1, 0, 0); + 0, 0, 0, main_low_prio - 1, 0, K_NO_WAIT); rc = k_poll(wait_events, ARRAY_SIZE(wait_events), K_SECONDS(1)); @@ -302,7 +303,7 @@ void test_poll_wait(void) K_THREAD_STACK_SIZEOF(test_stack), poll_wait_helper, (void *)1, 0, 0, old_prio + 1, - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); /* semaphore */ rc = k_poll(wait_events, ARRAY_SIZE(wait_events), K_SECONDS(1)); @@ -419,7 +420,8 @@ void test_poll_cancel(bool is_main_low_prio) k_thread_create(&test_thread, test_stack, K_THREAD_STACK_SIZEOF(test_stack), poll_cancel_helper, (void *)1, 0, 0, - main_low_prio - 1, K_USER | K_INHERIT_PERMS, 0); + main_low_prio - 1, K_USER | K_INHERIT_PERMS, + K_NO_WAIT); rc = k_poll(cancel_events, ARRAY_SIZE(cancel_events), K_SECONDS(1)); @@ -519,7 +521,7 @@ void test_poll_multi(void) k_thread_create(&test_thread, test_stack, K_THREAD_STACK_SIZEOF(test_stack), multi, 0, 0, 0, main_low_prio - 1, - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); /* * create additional thread to add multiple(more than one) pending threads @@ -528,7 +530,7 @@ void test_poll_multi(void) k_thread_create(&test_loprio_thread, test_loprio_stack, K_THREAD_STACK_SIZEOF(test_loprio_stack), multi_lowprio, 0, 0, 0, main_low_prio + 1, - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); /* Allow lower priority thread to add poll event in the list */ k_sleep(K_MSEC(250)); @@ -596,7 +598,8 @@ void test_poll_threadstate(void) k_thread_create(&test_thread, test_stack, K_THREAD_STACK_SIZEOF(test_stack), threadstate, - ztest_tid, 0, 0, main_low_prio - 1, K_INHERIT_PERMS, 0); + ztest_tid, 0, 0, main_low_prio - 1, K_INHERIT_PERMS, + K_NO_WAIT); /* wait for spawn thread to take action */ zassert_equal(k_poll(&event, 1, K_SECONDS(1)), 0, ""); diff --git a/tests/kernel/queue/src/test_queue_contexts.c b/tests/kernel/queue/src/test_queue_contexts.c index 0b35e6f6c88a8..818131f9fc210 100644 --- a/tests/kernel/queue/src/test_queue_contexts.c +++ b/tests/kernel/queue/src/test_queue_contexts.c @@ -111,7 +111,7 @@ static void tqueue_thread_thread(struct k_queue *pqueue) /**TESTPOINT: thread-thread data passing via queue*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, pqueue, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); tqueue_append(pqueue); k_sem_take(&end_sema, K_FOREVER); k_thread_abort(tid); @@ -192,11 +192,11 @@ static void tqueue_get_2threads(struct k_queue *pqueue) k_sem_init(&end_sema, 0, 1); k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_get, pqueue, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_tid_t tid1 = k_thread_create(&tdata1, tstack1, STACK_SIZE, tThread_get, pqueue, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); /* Wait threads to initialize */ k_sleep(K_MSEC(10)); diff --git a/tests/kernel/queue/src/test_queue_loop.c b/tests/kernel/queue/src/test_queue_loop.c index dc864ea19e0ca..5ea0c9c465e62 100644 --- a/tests/kernel/queue/src/test_queue_loop.c +++ b/tests/kernel/queue/src/test_queue_loop.c @@ -94,7 +94,7 @@ static void tqueue_read_write(struct k_queue *pqueue) /**TESTPOINT: thread-isr-thread data passing via queue*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tThread_entry, pqueue, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); TC_PRINT("main queue append ---> "); tqueue_append(pqueue); diff --git a/tests/kernel/queue/src/test_queue_user.c b/tests/kernel/queue/src/test_queue_user.c index ea29bd67a0f85..02bd74a24b23f 100644 --- a/tests/kernel/queue/src/test_queue_user.c +++ b/tests/kernel/queue/src/test_queue_user.c @@ -100,7 +100,7 @@ void test_queue_supv_to_user(void) k_thread_create(&child_thread, child_stack, STACK_SIZE, child_thread_get, q, sem, NULL, K_HIGHEST_THREAD_PRIO, - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); k_yield(); diff --git a/tests/kernel/sched/deadline/src/main.c b/tests/kernel/sched/deadline/src/main.c index 67f7937cf0b80..70888ccefc8fb 100644 --- a/tests/kernel/sched/deadline/src/main.c +++ b/tests/kernel/sched/deadline/src/main.c @@ -56,7 +56,7 @@ void test_deadline(void) worker_stacks[i], STACK_SIZE, worker, INT_TO_POINTER(i), NULL, NULL, K_LOWEST_APPLICATION_THREAD_PRIO, - 0, 0); + 0, K_NO_WAIT); /* Positive-definite number with the bottom 8 bits * masked off to prevent aliasing where "very close" diff --git a/tests/kernel/sched/preempt/src/main.c b/tests/kernel/sched/preempt/src/main.c index 9fc961aafb30f..7846128b70a66 100644 --- a/tests/kernel/sched/preempt/src/main.c +++ b/tests/kernel/sched/preempt/src/main.c @@ -330,12 +330,12 @@ void test_preempt(void) k_thread_create(&worker_threads[i], worker_stacks[i], STACK_SIZE, worker, INT_TO_POINTER(i), NULL, NULL, - priority, 0, 0); + priority, 0, K_NO_WAIT); } k_thread_create(&manager_thread, manager_stack, STACK_SIZE, manager, NULL, NULL, NULL, - K_LOWEST_APPLICATION_THREAD_PRIO, 0, 0); + K_LOWEST_APPLICATION_THREAD_PRIO, 0, K_NO_WAIT); /* We don't control the priority of this thread so can't make * it part of the test. Just get out of the way until the diff --git a/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c b/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c index 176575e0d7266..5438527cafaf3 100644 --- a/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c +++ b/tests/kernel/sched/schedule_api/src/test_priority_scheduling.c @@ -80,7 +80,8 @@ void test_priority_scheduling(void) for (int i = 0; i < NUM_THREAD; i++) { tid[i] = k_thread_create(&t[i], tstacks[i], STACK_SIZE, thread_tslice, INT_TO_POINTER(i), NULL, NULL, - K_PRIO_PREEMPT(BASE_PRIORITY + i), 0, 0); + K_PRIO_PREEMPT(BASE_PRIORITY + i), 0, + K_NO_WAIT); } while (count < ITRERATION_COUNT) { diff --git a/tests/kernel/sched/schedule_api/src/test_sched_is_preempt_thread.c b/tests/kernel/sched/schedule_api/src/test_sched_is_preempt_thread.c index 1178d313db165..58087517f2567 100644 --- a/tests/kernel/sched/schedule_api/src/test_sched_is_preempt_thread.c +++ b/tests/kernel/sched/schedule_api/src/test_sched_is_preempt_thread.c @@ -72,14 +72,14 @@ void test_sched_is_preempt_thread(void) /*create preempt thread*/ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, tpreempt_ctx, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), 0, 0); + K_PRIO_PREEMPT(1), 0, K_NO_WAIT); k_sem_take(&end_sema, K_FOREVER); k_thread_abort(tid); /*create coop thread*/ tid = k_thread_create(&tdata, tstack, STACK_SIZE, tcoop_ctx, NULL, NULL, NULL, - K_PRIO_COOP(1), 0, 0); + K_PRIO_COOP(1), 0, K_NO_WAIT); k_sem_take(&end_sema, K_FOREVER); k_thread_abort(tid); diff --git a/tests/kernel/sched/schedule_api/src/test_sched_priority.c b/tests/kernel/sched/schedule_api/src/test_sched_priority.c index eb3e47263bfcc..69a0254417ceb 100644 --- a/tests/kernel/sched/schedule_api/src/test_sched_priority.c +++ b/tests/kernel/sched/schedule_api/src/test_sched_priority.c @@ -41,7 +41,7 @@ void test_priority_cooperative(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, - spawn_prio, 0, 0); + spawn_prio, 0, K_NO_WAIT); /* checkpoint: current thread shouldn't preempted by higher thread */ zassert_true(last_prio == k_thread_priority_get(k_current_get()), NULL); k_sleep(K_MSEC(100)); @@ -76,7 +76,7 @@ void test_priority_preemptible(void) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, - spawn_prio, 0, 0); + spawn_prio, 0, K_NO_WAIT); /* checkpoint: thread is preempted by higher thread */ zassert_true(last_prio == spawn_prio, NULL); @@ -86,7 +86,7 @@ void test_priority_preemptible(void) spawn_prio = last_prio + 1; tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, - spawn_prio, 0, 0); + spawn_prio, 0, K_NO_WAIT); /* checkpoint: thread is not preempted by lower thread */ zassert_false(last_prio == spawn_prio, NULL); k_thread_abort(tid); diff --git a/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c b/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c index dc9a916aba88e..d1a01a3561120 100644 --- a/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c +++ b/tests/kernel/sched/schedule_api/src/test_sched_timeslice_and_lock.c @@ -59,7 +59,8 @@ static void spawn_threads(int sleep_sec) STACK_SIZE, thread_entry, INT_TO_POINTER(i), INT_TO_POINTER(sleep_sec), - NULL, tdata[i].priority, 0, 0); + NULL, tdata[i].priority, 0, + K_NO_WAIT); } } @@ -212,7 +213,7 @@ void test_pending_thread_wakeup(void) k_tid_t tid = k_thread_create(&t, tstack, STACK_SIZE, (k_thread_entry_t)coop_thread, NULL, NULL, NULL, - K_PRIO_COOP(1), 0, 0); + K_PRIO_COOP(1), 0, K_NO_WAIT); zassert_false(executed == 1, "The thread didn't wait" " for semaphore acquisition"); @@ -434,7 +435,7 @@ void test_wakeup_expired_timer_thread(void) { k_tid_t tid = k_thread_create(&tthread[0], tstack, STACK_SIZE, thread_handler, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), 0, 0); + K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_sem_take(&timer_sema, K_FOREVER); /* wakeup a thread if the timer is expired */ k_wakeup(tid); diff --git a/tests/kernel/sched/schedule_api/src/test_sched_timeslice_reset.c b/tests/kernel/sched/schedule_api/src/test_sched_timeslice_reset.c index 102d9e885fc70..aaa29a0422db7 100644 --- a/tests/kernel/sched/schedule_api/src/test_sched_timeslice_reset.c +++ b/tests/kernel/sched/schedule_api/src/test_sched_timeslice_reset.c @@ -124,7 +124,8 @@ void test_slice_reset(void) for (int i = 0; i < NUM_THREAD; i++) { tid[i] = k_thread_create(&t[i], tstacks[i], STACK_SIZE, thread_time_slice, NULL, NULL, NULL, - K_PRIO_PREEMPT(j), 0, 0); + K_PRIO_PREEMPT(j), 0, + K_NO_WAIT); } /* enable time slice*/ k_sched_time_slice_set(SLICE_SIZE, K_PRIO_PREEMPT(0)); diff --git a/tests/kernel/sched/schedule_api/src/test_slice_scheduling.c b/tests/kernel/sched/schedule_api/src/test_slice_scheduling.c index f03bf4eecc844..50429991159cd 100644 --- a/tests/kernel/sched/schedule_api/src/test_slice_scheduling.c +++ b/tests/kernel/sched/schedule_api/src/test_slice_scheduling.c @@ -101,7 +101,8 @@ void test_slice_scheduling(void) tid[i] = k_thread_create(&t[i], tstacks[i], STACK_SIZE, thread_tslice, INT_TO_POINTER(i), NULL, NULL, - K_PRIO_PREEMPT(BASE_PRIORITY), 0, 0); + K_PRIO_PREEMPT(BASE_PRIORITY), 0, + K_NO_WAIT); } /* enable time slice*/ diff --git a/tests/kernel/sched/schedule_api/src/user_api.c b/tests/kernel/sched/schedule_api/src/user_api.c index 53abe613d3111..8318b4d3cdc6b 100644 --- a/tests/kernel/sched/schedule_api/src/user_api.c +++ b/tests/kernel/sched/schedule_api/src/user_api.c @@ -28,7 +28,7 @@ void test_user_k_wakeup(void) k_thread_create(&user_thread, ustack, STACK_SIZE, sleepy_thread, NULL, NULL, NULL, k_thread_priority_get(k_current_get()), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); k_yield(); /* Let thread run and start sleeping forever */ k_wakeup(&user_thread); @@ -62,7 +62,7 @@ void test_user_k_is_preempt(void) k_thread_create(&user_thread, ustack, STACK_SIZE, preempt_test_thread, NULL, NULL, NULL, k_thread_priority_get(k_current_get()), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); k_sem_take(&user_sem, K_FOREVER); @@ -72,7 +72,7 @@ void test_user_k_is_preempt(void) k_thread_create(&user_thread, ustack, STACK_SIZE, preempt_test_thread, NULL, NULL, NULL, K_PRIO_PREEMPT(1), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); k_sem_take(&user_sem, K_FOREVER); diff --git a/tests/kernel/semaphore/sema_api/src/main.c b/tests/kernel/semaphore/sema_api/src/main.c index a7538d5cc33f7..73d0e407c6844 100644 --- a/tests/kernel/semaphore/sema_api/src/main.c +++ b/tests/kernel/semaphore/sema_api/src/main.c @@ -34,7 +34,7 @@ static void tsema_thread_thread(struct k_sem *psem) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, psem, NULL, NULL, K_PRIO_PREEMPT(0), - K_USER | K_INHERIT_PERMS, 0); + K_USER | K_INHERIT_PERMS, K_NO_WAIT); zassert_false(k_sem_take(psem, K_FOREVER), NULL); /*clean the spawn thread avoid side effect in next TC*/ diff --git a/tests/kernel/sleep/src/main.c b/tests/kernel/sleep/src/main.c index c10029131c897..09de55fa9caf5 100644 --- a/tests/kernel/sleep/src/main.c +++ b/tests/kernel/sleep/src/main.c @@ -198,7 +198,7 @@ void test_sleep(void) THREAD_STACK, (k_thread_entry_t) test_thread, 0, 0, NULL, TEST_THREAD_PRIORITY, - 0, 0); + 0, K_NO_WAIT); TC_PRINT("Test thread started: id = %p\n", test_thread_id); @@ -206,7 +206,7 @@ void test_sleep(void) helper_thread_stack, THREAD_STACK, (k_thread_entry_t) helper_thread, 0, 0, NULL, HELPER_THREAD_PRIORITY, - 0, 0); + 0, K_NO_WAIT); TC_PRINT("Helper thread started: id = %p\n", helper_thread_id); diff --git a/tests/kernel/spinlock/src/main.c b/tests/kernel/spinlock/src/main.c index 12a4d8ae454d3..0d5b1fbd9de1d 100644 --- a/tests/kernel/spinlock/src/main.c +++ b/tests/kernel/spinlock/src/main.c @@ -118,7 +118,7 @@ void test_spinlock_bounce(void) k_thread_create(&cpu1_thread, cpu1_stack, CPU1_STACK_SIZE, cpu1_fn, NULL, NULL, NULL, - 0, 0, 0); + 0, 0, K_NO_WAIT); k_busy_wait(10); diff --git a/tests/kernel/stack/stack_api/src/test_stack_contexts.c b/tests/kernel/stack/stack_api/src/test_stack_contexts.c index 15c149a3fd416..f69f765beb2e2 100644 --- a/tests/kernel/stack/stack_api/src/test_stack_contexts.c +++ b/tests/kernel/stack/stack_api/src/test_stack_contexts.c @@ -64,7 +64,7 @@ static void tstack_thread_thread(struct k_stack *pstack) k_tid_t tid = k_thread_create(&thread_data, threadstack, STACK_SIZE, tThread_entry, pstack, NULL, NULL, K_PRIO_PREEMPT(0), K_USER | - K_INHERIT_PERMS, 0); + K_INHERIT_PERMS, K_NO_WAIT); tstack_push(pstack); k_sem_take(&end_sema, K_FOREVER); @@ -150,7 +150,8 @@ void test_stack_alloc_thread2thread(void) /**TESTPOINT: thread-thread data passing via stack*/ k_tid_t tid = k_thread_create(&thread_data, threadstack, STACK_SIZE, tThread_entry, &kstack_test_alloc, - NULL, NULL, K_PRIO_PREEMPT(0), 0, 0); + NULL, NULL, K_PRIO_PREEMPT(0), 0, + K_NO_WAIT); tstack_push(&kstack_test_alloc); k_sem_take(&end_sema, K_FOREVER); diff --git a/tests/kernel/stack/stack_usage/src/main.c b/tests/kernel/stack/stack_usage/src/main.c index aad30d6f984f6..4333aec69ee63 100644 --- a/tests/kernel/stack/stack_usage/src/main.c +++ b/tests/kernel/stack/stack_usage/src/main.c @@ -157,7 +157,7 @@ static void test_single_stack_play(void) k_tid_t tid = k_thread_create(&thread_data, threadstack, TSTACK_SIZE, thread_entry_fn_single, &stack1, NULL, NULL, K_PRIO_PREEMPT(0), K_USER | - K_INHERIT_PERMS, 0); + K_INHERIT_PERMS, K_NO_WAIT); /* Let the child thread run */ k_sem_take(&end_sema, K_FOREVER); @@ -186,7 +186,7 @@ static void test_dual_stack_play(void) k_tid_t tid = k_thread_create(&thread_data, threadstack, TSTACK_SIZE, thread_entry_fn_dual, &stack1, &stack2, NULL, K_PRIO_PREEMPT(0), K_USER | - K_INHERIT_PERMS, 0); + K_INHERIT_PERMS, K_NO_WAIT); for (i = 0U; i < STACK_LEN; i++) { /* Push items to stack2 */ @@ -215,7 +215,7 @@ static void test_isr_stack_play(void) k_tid_t tid = k_thread_create(&thread_data, threadstack, TSTACK_SIZE, thread_entry_fn_isr, &stack1, &stack2, NULL, K_PRIO_PREEMPT(0), - K_INHERIT_PERMS, 0); + K_INHERIT_PERMS, K_NO_WAIT); /* Push items to stack2 */ diff --git a/tests/kernel/threads/dynamic_thread/src/main.c b/tests/kernel/threads/dynamic_thread/src/main.c index ce2e5adedcf80..8c5863e477f79 100644 --- a/tests/kernel/threads/dynamic_thread/src/main.c +++ b/tests/kernel/threads/dynamic_thread/src/main.c @@ -50,7 +50,7 @@ static void create_dynamic_thread(void) tid = k_thread_create(dyn_thread, dyn_thread_stack, STACKSIZE, dyn_thread_entry, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_USER, 0); + K_PRIO_PREEMPT(0), K_USER, K_NO_WAIT); k_object_access_grant(&start_sem, tid); k_object_access_grant(&end_sem, tid); @@ -76,7 +76,7 @@ static void permission_test(void) tid = k_thread_create(dyn_thread, dyn_thread_stack, STACKSIZE, dyn_thread_entry, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_USER, 0); + K_PRIO_PREEMPT(0), K_USER, K_NO_WAIT); k_object_access_grant(&start_sem, tid); diff --git a/tests/kernel/threads/thread_apis/src/main.c b/tests/kernel/threads/thread_apis/src/main.c index 9c3f5067c5cd6..cdca80a02eb36 100644 --- a/tests/kernel/threads/thread_apis/src/main.c +++ b/tests/kernel/threads/thread_apis/src/main.c @@ -95,7 +95,7 @@ void test_customdata_get_set_coop(void) { k_tid_t tid = k_thread_create(&tdata_custom, tstack_custom, STACK_SIZE, customdata_entry, NULL, NULL, NULL, - K_PRIO_COOP(1), 0, 0); + K_PRIO_COOP(1), 0, K_NO_WAIT); k_sleep(K_MSEC(500)); @@ -130,7 +130,7 @@ void test_thread_name_get_set(void) /* Set and get child thread's name */ k_tid_t tid = k_thread_create(&tdata_name, tstack_name, STACK_SIZE, thread_name_entry, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), 0, 0); + K_PRIO_PREEMPT(1), 0, K_NO_WAIT); ret = k_thread_name_set(tid, "customdata"); zassert_equal(ret, 0, "k_thread_name_set() failed"); @@ -198,7 +198,7 @@ void test_thread_name_user_get_set(void) /* Set and get child thread's name */ k_tid_t tid = k_thread_create(&tdata_name, tstack_name, STACK_SIZE, thread_name_entry, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), K_USER, 0); + K_PRIO_PREEMPT(1), K_USER, K_NO_WAIT); ret = k_thread_name_set(tid, "customdata"); zassert_equal(ret, 0, "k_thread_name_set() failed"); ret = k_thread_name_copy(tid, thread_name, sizeof(thread_name)); @@ -223,7 +223,7 @@ void test_customdata_get_set_preempt(void) /** TESTPOINT: custom data of preempt thread */ k_tid_t tid = k_thread_create(&tdata_custom, tstack_custom, STACK_SIZE, customdata_entry, NULL, NULL, NULL, - K_PRIO_PREEMPT(0), K_USER, 0); + K_PRIO_PREEMPT(0), K_USER, K_NO_WAIT); k_sleep(K_MSEC(500)); diff --git a/tests/kernel/threads/thread_apis/src/test_essential_thread.c b/tests/kernel/threads/thread_apis/src/test_essential_thread.c index 3c22251865e17..7a0bc07b0de64 100644 --- a/tests/kernel/threads/thread_apis/src/test_essential_thread.c +++ b/tests/kernel/threads/thread_apis/src/test_essential_thread.c @@ -41,7 +41,8 @@ void test_essential_thread_operation(void) { k_tid_t tid = k_thread_create(&kthread_thread, kthread_stack, STACKSIZE, (k_thread_entry_t)thread_entry, NULL, - NULL, NULL, K_PRIO_PREEMPT(0), 0, 0); + NULL, NULL, K_PRIO_PREEMPT(0), 0, + K_NO_WAIT); k_sem_take(&sync_sem, K_FOREVER); k_thread_abort(tid); diff --git a/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c b/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c index d7c479a120a00..0a72f498abcd3 100644 --- a/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c +++ b/tests/kernel/threads/thread_apis/src/test_kthread_for_each.c @@ -62,7 +62,7 @@ void test_k_thread_foreach(void) /* Create new thread which should add a new entry to the thread list */ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, (k_thread_entry_t)thread_entry, NULL, - NULL, NULL, K_PRIO_PREEMPT(0), 0, 0); + NULL, NULL, K_PRIO_PREEMPT(0), 0, K_NO_WAIT); k_sleep(K_MSEC(1)); /* Call k_thread_foreach() and check diff --git a/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c b/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c index 4cc1edd90cf50..18ecaa13ef0a7 100644 --- a/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c +++ b/tests/kernel/threads/thread_apis/src/test_threads_cancel_abort.c @@ -43,7 +43,7 @@ void test_threads_abort_self(void) { execute_flag = 0; k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_abort, - NULL, NULL, NULL, 0, K_USER, 0); + NULL, NULL, NULL, 0, K_USER, K_NO_WAIT); k_sleep(K_MSEC(100)); /**TESTPOINT: spawned thread executed but abort itself*/ zassert_true(execute_flag == 1, NULL); @@ -64,7 +64,7 @@ void test_threads_abort_others(void) execute_flag = 0; k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, - 0, K_USER, 0); + 0, K_USER, K_NO_WAIT); k_thread_abort(tid); k_sleep(K_MSEC(100)); @@ -73,7 +73,7 @@ void test_threads_abort_others(void) tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, - 0, K_USER, 0); + 0, K_USER, K_NO_WAIT); k_sleep(K_MSEC(50)); k_thread_abort(tid); /**TESTPOINT: check running thread is aborted*/ @@ -93,7 +93,7 @@ void test_threads_abort_repeat(void) execute_flag = 0; k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, - 0, K_USER, 0); + 0, K_USER, K_NO_WAIT); k_thread_abort(tid); k_sleep(K_MSEC(100)); @@ -133,7 +133,7 @@ void test_abort_handler(void) { k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, (k_thread_entry_t)uthread_entry, NULL, NULL, NULL, - 0, 0, 0); + 0, 0, K_NO_WAIT); tdata.fn_abort = &abort_function; @@ -174,7 +174,7 @@ void test_delayed_thread_abort(void) */ k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, (k_thread_entry_t)delayed_thread_entry, NULL, NULL, NULL, - K_PRIO_PREEMPT(1), 0, 100); + K_PRIO_PREEMPT(1), 0, K_MSEC(100)); /* Give up CPU */ k_sleep(K_MSEC(50)); diff --git a/tests/kernel/threads/thread_apis/src/test_threads_set_priority.c b/tests/kernel/threads/thread_apis/src/test_threads_set_priority.c index f45168ed2d832..10b2240d44f12 100644 --- a/tests/kernel/threads/thread_apis/src/test_threads_set_priority.c +++ b/tests/kernel/threads/thread_apis/src/test_threads_set_priority.c @@ -73,7 +73,8 @@ void test_threads_priority_set(void) k_tid_t thread2_id = k_thread_create(&tdata, tstack, STACK_SIZE, (k_thread_entry_t)thread2_set_prio_test, - NULL, NULL, NULL, thread2_prio, 0, 0); + NULL, NULL, NULL, thread2_prio, 0, + K_NO_WAIT); /* Lower the priority of thread2 */ k_thread_priority_set(thread2_id, thread2_prio + 2); diff --git a/tests/kernel/threads/thread_apis/src/test_threads_spawn.c b/tests/kernel/threads/thread_apis/src/test_threads_spawn.c index 4b9c15daa4f6f..8d715534dd384 100644 --- a/tests/kernel/threads/thread_apis/src/test_threads_spawn.c +++ b/tests/kernel/threads/thread_apis/src/test_threads_spawn.c @@ -49,7 +49,7 @@ void test_threads_spawn_params(void) { k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_params, tp1, INT_TO_POINTER(tp2), tp3, 0, - K_USER, 0); + K_USER, K_NO_WAIT); k_sleep(K_MSEC(100)); } @@ -67,7 +67,7 @@ void test_threads_spawn_priority(void) /* spawn thread with higher priority */ spawn_prio = k_thread_priority_get(k_current_get()) - 1; k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_priority, - NULL, NULL, NULL, spawn_prio, K_USER, 0); + NULL, NULL, NULL, spawn_prio, K_USER, K_NO_WAIT); k_sleep(K_MSEC(100)); } @@ -85,7 +85,7 @@ void test_threads_spawn_delay(void) /* spawn thread with higher priority */ tp2 = 10; k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry_delay, - NULL, NULL, NULL, 0, K_USER, 120); + NULL, NULL, NULL, 0, K_USER, K_MSEC(120)); /* 100 < 120 ensure spawn thread not start */ k_sleep(K_MSEC(100)); /* checkpoint: check spawn thread not execute */ diff --git a/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c b/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c index 25d517b0b524c..f89a7dbd4ab25 100644 --- a/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c +++ b/tests/kernel/threads/thread_apis/src/test_threads_suspend_resume.c @@ -26,7 +26,7 @@ static void threads_suspend_resume(int prio) k_tid_t tid = k_thread_create(&tdata, tstack, STACK_SIZE, thread_entry, NULL, NULL, NULL, - create_prio, K_USER, 0); + create_prio, K_USER, K_NO_WAIT); /* checkpoint: suspend current thread */ k_thread_suspend(tid); k_sleep(K_MSEC(100)); diff --git a/tests/kernel/workq/work_queue/src/main.c b/tests/kernel/workq/work_queue/src/main.c index e9b35fa509518..412956caf03ff 100644 --- a/tests/kernel/workq/work_queue/src/main.c +++ b/tests/kernel/workq/work_queue/src/main.c @@ -117,7 +117,7 @@ static void delayed_test_items_submit(void) k_thread_create(&co_op_data, co_op_stack, STACK_SIZE, (k_thread_entry_t)coop_work_main, - NULL, NULL, NULL, K_PRIO_COOP(10), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(10), 0, K_NO_WAIT); for (i = 0; i < NUM_TEST_ITEMS; i += 2) { TC_PRINT(" - Submitting work %d from preempt thread\n", i + 1); @@ -266,7 +266,7 @@ static void test_delayed_submit(void) k_thread_create(&co_op_data, co_op_stack, STACK_SIZE, (k_thread_entry_t)coop_delayed_work_main, - NULL, NULL, NULL, K_PRIO_COOP(10), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(10), 0, K_NO_WAIT); for (i = 0; i < NUM_TEST_ITEMS; i += 2) { TC_PRINT(" - Submitting delayed work %d from" @@ -315,7 +315,7 @@ static void test_delayed_cancel(void) k_thread_create(&co_op_data, co_op_stack, STACK_SIZE, (k_thread_entry_t)coop_delayed_work_cancel_main, - NULL, NULL, NULL, K_HIGHEST_THREAD_PRIO, 0, 0); + NULL, NULL, NULL, K_HIGHEST_THREAD_PRIO, 0, K_NO_WAIT); TC_PRINT(" - Waiting for work to finish\n"); k_sleep(WORK_ITEM_WAIT_ALIGNED); @@ -401,7 +401,7 @@ static void test_delayed_resubmit_thread(void) k_thread_create(&co_op_data, co_op_stack, STACK_SIZE, (k_thread_entry_t)coop_delayed_work_resubmit, - NULL, NULL, NULL, K_PRIO_COOP(10), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(10), 0, K_NO_WAIT); TC_PRINT(" - Waiting for work to finish\n"); k_sleep(WORK_ITEM_WAIT_ALIGNED); diff --git a/tests/net/buf/src/main.c b/tests/net/buf/src/main.c index 400b821bf3e51..6a7672336648b 100644 --- a/tests/net/buf/src/main.c +++ b/tests/net/buf/src/main.c @@ -189,7 +189,7 @@ static void net_buf_test_3(void) k_thread_create(&test_3_thread_data, test_3_thread_stack, K_THREAD_STACK_SIZEOF(test_3_thread_stack), (k_thread_entry_t) test_3_thread, &fifo, &sema, NULL, - K_PRIO_COOP(7), 0, 0); + K_PRIO_COOP(7), 0, K_NO_WAIT); zassert_true(k_sem_take(&sema, TEST_TIMEOUT) == 0, "Timeout while waiting for semaphore"); diff --git a/tests/net/context/src/main.c b/tests/net/context/src/main.c index 9b62f208bea79..e6e007144af3a 100644 --- a/tests/net/context/src/main.c +++ b/tests/net/context/src/main.c @@ -704,7 +704,7 @@ static k_tid_t start_timeout_v6_thread(s32_t timeout) (k_thread_entry_t)timeout_thread, udp_v6_ctx, INT_TO_POINTER(AF_INET6), INT_TO_POINTER(timeout), - K_PRIO_COOP(7), 0, 0); + K_PRIO_COOP(7), 0, K_NO_WAIT); } static k_tid_t start_timeout_v4_thread(s32_t timeout) @@ -713,7 +713,7 @@ static k_tid_t start_timeout_v4_thread(s32_t timeout) (k_thread_entry_t)timeout_thread, udp_v4_ctx, INT_TO_POINTER(AF_INET), INT_TO_POINTER(timeout), - K_PRIO_COOP(7), 0, 0); + K_PRIO_COOP(7), 0, K_NO_WAIT); } static void net_ctx_recv_v6_timeout(void) diff --git a/tests/net/mgmt/src/mgmt.c b/tests/net/mgmt/src/mgmt.c index 89165a944b5fc..8fffa4512f9fd 100644 --- a/tests/net/mgmt/src/mgmt.c +++ b/tests/net/mgmt/src/mgmt.c @@ -247,7 +247,7 @@ static void initialize_event_tests(void) k_thread_create(&thrower_thread_data, thrower_stack, K_THREAD_STACK_SIZEOF(thrower_stack), (k_thread_entry_t)thrower_thread, - NULL, NULL, NULL, K_PRIO_COOP(7), 0, 0); + NULL, NULL, NULL, K_PRIO_COOP(7), 0, K_NO_WAIT); } static int test_core_event(u32_t event, bool (*func)(void))