diff --git a/boards/arm/nrf52_pca20020/board.c b/boards/arm/nrf52_pca20020/board.c index 4de76762c50..b23707de466 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 dd7ded9f0e6..cf96e92b1d4 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 3633ef5b385..cf35f8cb50a 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 e92dc890b10..bc00ab445a9 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 973f8eca1ff..911ba48139e 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 329e5646ce4..1312b32d42e 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 c652a613935..c3254387335 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 baf21d2fd0d..3e9a5329abf 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 2c968616529..209cee19a14 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 5f40a7508eb..2d53673ced0 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 3c36478c6bd..7aa23ad511a 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 43be4e340b9..76c8b40bb4b 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 650e8c9a9fe..483b668c48e 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 10b88fcfafc..af8d793f097 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 dd561bcb08e..6d335d47977 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 171c26f8cbd..ad0048d35b8 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 07036ecc420..9b9833beaff 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 ef99413c237..e998906301d 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 14770a3ffda..e4591ed7f3e 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 656f1c35ec6..f1679099d17 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 98a8e133e0c..fde1dedb662 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 3b728b476ca..8458fc08d19 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 91ec61cf465..6f7cd22b4eb 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 b57f9f85c07..78f4c753513 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 f88dbd09301..a51dc8a2e5b 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 144d8abe099..5d242515113 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 723539576c2..77044600702 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 @@ data: /* 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 96795cddd18..253bd8c69b0 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 44f3ce8520c..8a585f45ad6 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 d9525099040..64c7decd1c9 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 cf632eeecfc..27343aaf1f2 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 ac1092a658d..5cf4de4009a 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 cdf3aa090a2..1a770435613 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 5872776a263..545bfea0b3b 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 39dee337454..5906690a6a6 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 dd767251cfd..4f0d264a7db 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 c4156672acf..4d729653d45 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 2f75176bc1f..930721254e0 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 0c4d69a6830..c1f21aeb849 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 44748314706..ebe89eb7726 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 9dded7c78de..340021658a1 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 d6161cd23e5..a150a34e43e 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 8c3031e2f12..b18024bbde3 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 10194ccc57b..571c5c5745b 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 746ba634e70..b4703a9af3e 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 74cad1ea717..7b526545556 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 9c7ad8e97db..9bcc77875d3 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 b0fcc749718..ab2497cd0b1 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 a8aae0c9317..8d5d0cf68bf 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 09adec7db25..00b9ad1ff44 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 ac0582811ce..04f800b6486 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 b18b94f8eb9..b45a1eec577 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 0ff19b924fe..b73c0248fb4 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 4a9fb1a4a24..2efae8ed221 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 770572d4677..fb6360beef7 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 c65dbf5a1ab..ec663fceb6d 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 fd1e0936544..7651de242c9 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 a4f3b7ceb85..6c0fc595079 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 ba11edf3896..f1fcef73b4f 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 483bb301fad..1c2d16599ed 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 24912c3d32b..78c76bcaf8e 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 da79e89d914..1611ce6e77a 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 cd06df301aa..f81a8d43069 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 090f3f4d196..e0e1470c722 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 e5ad9185537..d50bc7af6db 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 2b3cc38e6db..56b7e8c08f1 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 6c1bbb8425b..79d48d209c8 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 227c74ae7d8..318bc635618 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 586efd74799..674e3376f91 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 1d23b3b860a..27f98793c26 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 2b028023e63..46abd6f2927 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 70ab1348b1b..cbc20258c04 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 2653ba57d6b..a7a0fc90868 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 b5076039993..3bed8291be2 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 9668b686025..0813aabef19 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 6f737b018a2..5fcf7894acd 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 ce4a6472a72..2a23f55116a 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 aaeccbebaf1..535ea7422fb 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 0c19f353548..4b96b128cf0 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 4451bfc234e..b0654bdbf79 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 dd9e64bf8c1..d4e29a10be4 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 eef08ba6c53..85cfd2fd419 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 f85a2956bf7..e92e8887f05 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 b9684f7c221..4f5b3f715d5 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 9e06f37e50f..e2edbaf8988 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 536a1f7bb0d..9feecac3fb9 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 74b733c2834..5dda5a308d6 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 2f323cd0277..af5fbb2cbac 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 4bd0c0deaac..b6b3852b90e 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 262bf201609..7fa7785fd5b 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 f83a6a069cc..dff6c567e97 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 242295d3c07..c842f586f2c 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 443b5335976..56c96464837 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 f54e4581fea..862c24d22fc 100644 --- a/tests/drivers/counter/counter_basic_api/src/test_counter.c +++ b/tests/drivers/counter/counter_basic_api/src/test_counter.c @@ -120,7 +120,7 @@ static void test_all_instances(counter_test_func_t func, } 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 43173cdc4b0..90571fa195d 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 f7ecdc59aaa..258ab96e6ed 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 28c01d941d8..3b87ad1c264 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 f6b2b0ee91c..cc359e13766 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 ac71ee2d545..64df4529627 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 b5103e51080..df751407f23 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 987748c1a24..52206db4294 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 fbf0badd6a6..c0b94e3bf17 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 410701f1a67..a78dc27bdbb 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 04c8e6f0b11..00805bd66db 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 1b4fd79eded..d2ffb38f3f5 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 ead59963204..d743c43d346 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 d8ec1e1318c..c7bb011ca0f 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 62ad3dab27e..136b7e69324 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 65f07864b16..3000c23b5be 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 2b0ceb55d0f..032170b0e8d 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 5ec692bfd07..0c05bd60b9c 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 cf278f9ffc6..90e5034faa7 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 e3587684906..c577230b497 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 0d1cb0f5bd6..fa1df8cb22a 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 1a4fe592887..680787a81a4 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 d32935773e7..0b35e6f6c88 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 2369e219725..67f7937cf0b 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 df65df964d6..9fc961aafb3 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 2e4a01f8d30..176575e0d72 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 4d0dc9183f7..eb3e47263bf 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 8beef229486..dc9a916aba8 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 a300ec1bfea..0018ae23586 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 940c30f0699..9c3f5067c5c 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 a13fc8f8363..d7c479a120a 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 181e8dec916..4cc1edd90cf 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 63f51439e51..4b9c15daa4f 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 fe1c6f730fe..25d517b0b52 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 03e3fad9b6a..473585e8246 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 c7f95dbde7e..393724da28b 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 43a28c65258..3202ddbdb7e 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); } }