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 <peter.bigot@nordicsemi.no>
This commit is contained in:
Peter Bigot 2019-10-06 14:02:31 -05:00 committed by Anas Nashif
commit 6e5db350b2
130 changed files with 229 additions and 229 deletions

View file

@ -30,7 +30,7 @@ static int pwr_ctrl_init(struct device *dev)
gpio_pin_configure(gpio, cfg->pin, GPIO_DIR_OUT); gpio_pin_configure(gpio, cfg->pin, GPIO_DIR_OUT);
gpio_pin_write(gpio, cfg->pin, 1); 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; return 0;
} }

View file

@ -55,7 +55,7 @@ int bt_hci_transport_setup(struct device *h4)
* It is critical (!) to wait here, so that all bytes * It is critical (!) to wait here, so that all bytes
* on the lines are received and drained correctly. * on the lines are received and drained correctly.
*/ */
k_sleep(1); k_sleep(K_MSEC(1));
/* Drain bytes */ /* Drain bytes */
while (uart_fifo_read(h4, &c, 1)) { while (uart_fifo_read(h4, &c, 1)) {

View file

@ -608,11 +608,11 @@ static void tx_thread(void)
switch (h5.link_state) { switch (h5.link_state) {
case UNINIT: case UNINIT:
/* FIXME: send sync */ /* FIXME: send sync */
k_sleep(100); k_sleep(K_MSEC(100));
break; break;
case INIT: case INIT:
/* FIXME: send conf */ /* FIXME: send conf */
k_sleep(100); k_sleep(K_MSEC(100));
break; break;
case ACTIVE: case ACTIVE:
buf = net_buf_get(&h5.tx_queue, K_FOREVER); buf = net_buf_get(&h5.tx_queue, K_FOREVER);

View file

@ -407,7 +407,7 @@ static int bt_spi_send(struct net_buf *buf)
if (!pending) { if (!pending) {
break; break;
} }
k_sleep(1); k_sleep(K_MSEC(1));
} }
k_sem_take(&sem_busy, K_FOREVER); k_sem_take(&sem_busy, K_FOREVER);

View file

@ -42,7 +42,7 @@ struct ili9340_data {
static void ili9340_exit_sleep(struct ili9340_data *data) static void ili9340_exit_sleep(struct ili9340_data *data)
{ {
ili9340_transmit(data, ILI9340_CMD_EXIT_SLEEP, NULL, 0); ili9340_transmit(data, ILI9340_CMD_EXIT_SLEEP, NULL, 0);
k_sleep(120); k_sleep(K_MSEC(120));
} }
static int ili9340_init(struct device *dev) 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 #ifdef DT_INST_0_ILITEK_ILI9340_RESET_GPIOS_CONTROLLER
LOG_DBG("Resetting display driver"); LOG_DBG("Resetting display driver");
gpio_pin_write(data->reset_gpio, DT_INST_0_ILITEK_ILI9340_RESET_GPIOS_PIN, 1); 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); 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); gpio_pin_write(data->reset_gpio, DT_INST_0_ILITEK_ILI9340_RESET_GPIOS_PIN, 1);
k_sleep(5); k_sleep(K_MSEC(5));
#endif #endif
LOG_DBG("Initializing LCD"); LOG_DBG("Initializing LCD");

View file

@ -22,7 +22,7 @@ void ili9340_lcd_init(struct ili9340_data *p_ili9340)
cmd = ILI9340_CMD_SOFTWARE_RESET; cmd = ILI9340_CMD_SOFTWARE_RESET;
ili9340_transmit(p_ili9340, cmd, NULL, 0); ili9340_transmit(p_ili9340, cmd, NULL, 0);
k_sleep(5); k_sleep(K_MSEC(5));
cmd = ILI9341_CMD_POWER_CTRL_B; cmd = ILI9341_CMD_POWER_CTRL_B;
data[0] = 0x00U; data[0] = 0x00U;
@ -166,7 +166,7 @@ void ili9340_lcd_init(struct ili9340_data *p_ili9340)
cmd = ILI9340_CMD_EXIT_SLEEP; cmd = ILI9340_CMD_EXIT_SLEEP;
ili9340_transmit(p_ili9340, cmd, NULL, 0); ili9340_transmit(p_ili9340, cmd, NULL, 0);
k_sleep(120); k_sleep(K_MSEC(120));
/* Display Off */ /* Display Off */
cmd = ILI9340_CMD_DISPLAY_OFF; cmd = ILI9340_CMD_DISPLAY_OFF;

View file

@ -81,7 +81,7 @@ void st7789v_transmit(struct st7789v_data *data, u8_t cmd,
static void st7789v_exit_sleep(struct st7789v_data *data) static void st7789v_exit_sleep(struct st7789v_data *data)
{ {
st7789v_transmit(data, ST7789V_CMD_SLEEP_OUT, NULL, 0); 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) 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"); LOG_DBG("Resetting display");
#ifdef DT_INST_0_SITRONIX_ST7789V_RESET_GPIOS_CONTROLLER #ifdef DT_INST_0_SITRONIX_ST7789V_RESET_GPIOS_CONTROLLER
gpio_pin_write(data->reset_gpio, ST7789V_RESET_PIN, 1); 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); 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); gpio_pin_write(data->reset_gpio, ST7789V_RESET_PIN, 1);
k_sleep(20); k_sleep(K_MSEC(20));
#else #else
st7789v_transmit(p_st7789v, ST7789V_CMD_SW_RESET, NULL, 0); st7789v_transmit(p_st7789v, ST7789V_CMD_SW_RESET, NULL, 0);
k_sleep(5); k_sleep(K_MSEC(5));
#endif #endif
} }

View file

@ -325,7 +325,7 @@ static int enc424j600_tx(struct device *dev, struct net_pkt *pkt)
enc424j600_write_sbc(dev, ENC424J600_1BC_SETTXRTS); enc424j600_write_sbc(dev, ENC424J600_1BC_SETTXRTS);
do { do {
k_sleep(1); k_sleep(K_MSEC(1));
enc424j600_read_sfru(dev, ENC424J600_SFRX_ECON1L, &tmp); enc424j600_read_sfru(dev, ENC424J600_SFRX_ECON1L, &tmp);
} while (tmp & ENC424J600_ECON1_TXRTS); } while (tmp & ENC424J600_ECON1_TXRTS);
@ -545,12 +545,12 @@ static int enc424j600_stop_device(struct device *dev)
ENC424J600_ECON1_RXEN); ENC424J600_ECON1_RXEN);
do { do {
k_sleep(10U); k_sleep(K_MSEC(10U));
enc424j600_read_sfru(dev, ENC424J600_SFRX_ESTATL, &tmp); enc424j600_read_sfru(dev, ENC424J600_SFRX_ESTATL, &tmp);
} while (tmp & ENC424J600_ESTAT_RXBUSY); } while (tmp & ENC424J600_ESTAT_RXBUSY);
do { do {
k_sleep(10U); k_sleep(K_MSEC(10U));
enc424j600_read_sfru(dev, ENC424J600_SFRX_ECON1L, &tmp); enc424j600_read_sfru(dev, ENC424J600_SFRX_ECON1L, &tmp);
} while (tmp & ENC424J600_ECON1_TXRTS); } while (tmp & ENC424J600_ECON1_TXRTS);

View file

@ -106,7 +106,7 @@ int smsc_phy_regread(u8_t regoffset, u32_t *data)
val = 0U; val = 0U;
do { do {
k_sleep(1); k_sleep(K_MSEC(1));
time_out--; time_out--;
if (smsc_mac_regread(SMSC9220_MAC_MII_ACC, &val)) { if (smsc_mac_regread(SMSC9220_MAC_MII_ACC, &val)) {
return -1; return -1;
@ -152,7 +152,7 @@ int smsc_phy_regwrite(u8_t regoffset, u32_t data)
} }
do { do {
k_sleep(1); k_sleep(K_MSEC(1));
time_out--; time_out--;
if (smsc_mac_regread(SMSC9220_MAC_MII_ACC, &phycmd)) { if (smsc_mac_regread(SMSC9220_MAC_MII_ACC, &phycmd)) {
return -1; return -1;
@ -222,7 +222,7 @@ static int smsc_soft_reset(void)
SMSC9220->HW_CFG |= HW_CFG_SRST; SMSC9220->HW_CFG |= HW_CFG_SRST;
do { do {
k_sleep(1); k_sleep(K_MSEC(1));
time_out--; time_out--;
} while (time_out != 0U && (SMSC9220->HW_CFG & HW_CFG_SRST)); } 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 */ SMSC9220->FIFO_INT &= ~(0xFF); /* Clear 2 bottom nibbles */
/* This sleep is compulsory otherwise txmit/receive will fail. */ /* This sleep is compulsory otherwise txmit/receive will fail. */
k_sleep(2000); k_sleep(K_MSEC(2000));
return 0; return 0;
} }

View file

@ -87,7 +87,7 @@ static inline void disable_mcast_filter(ETH_HandleTypeDef *heth)
* at least four TX_CLK/RX_CLK clock cycles * at least four TX_CLK/RX_CLK clock cycles
*/ */
tmp = heth->Instance->MACFFR; tmp = heth->Instance->MACFFR;
k_sleep(1); k_sleep(K_MSEC(1));
heth->Instance->MACFFR = tmp; heth->Instance->MACFFR = tmp;
} }

View file

@ -47,7 +47,7 @@ static int mdio_bus_wait(Gmac *gmac)
return -ETIMEDOUT; return -ETIMEDOUT;
} }
k_sleep(10); k_sleep(K_MSEC(10));
} }
return 0; return 0;
@ -127,7 +127,7 @@ static int phy_soft_reset(const struct phy_sam_gmac_dev *phy)
return -ETIMEDOUT; return -ETIMEDOUT;
} }
k_sleep(50); k_sleep(K_MSEC(50));
retval = phy_read(phy, MII_BMCR, &phy_reg); retval = phy_read(phy, MII_BMCR, &phy_reg);
if (retval < 0) { if (retval < 0) {
@ -228,7 +228,7 @@ int phy_sam_gmac_auto_negotiate(const struct phy_sam_gmac_dev *phy,
goto auto_negotiate_exit; goto auto_negotiate_exit;
} }
k_sleep(100); k_sleep(K_MSEC(100));
retval = phy_read(phy, MII_BMSR, &val); retval = phy_read(phy, MII_BMSR, &val);
if (retval < 0) { if (retval < 0) {

View file

@ -140,7 +140,7 @@ static int i2s_stm32_set_clock(struct device *dev, u32_t bit_clk_freq)
} }
/* wait 1 ms */ /* wait 1 ms */
k_sleep(1); k_sleep(K_MSEC(1));
} }
LOG_DBG("PLLI2S is locked"); LOG_DBG("PLLI2S is locked");

View file

@ -489,7 +489,7 @@ static inline int lp5562_set_engine_exec_state(struct device *dev,
* Delay between consecutive I2C writes to * Delay between consecutive I2C writes to
* ENABLE register (00h) need to be longer than 488μs (typ.). * ENABLE register (00h) need to be longer than 488μs (typ.).
*/ */
k_sleep(1); k_sleep(K_MSEC(1));
return ret; return ret;
} }

View file

@ -96,7 +96,7 @@ static int imx_pwm_pin_set(struct device *dev, u32_t pwm,
} else { } else {
PWM_PWMCR_REG(base) = PWM_PWMCR_SWR(1); PWM_PWMCR_REG(base) = PWM_PWMCR_SWR(1);
do { do {
k_sleep(1); k_sleep(K_MSEC(1));
cr = PWM_PWMCR_REG(base); cr = PWM_PWMCR_REG(base);
} while ((PWM_PWMCR_SWR(cr)) && } while ((PWM_PWMCR_SWR(cr)) &&
(++wait_count < CONFIG_PWM_PWMSWR_LOOP)); (++wait_count < CONFIG_PWM_PWMSWR_LOOP));

View file

@ -755,7 +755,7 @@ static int adxl362_init(struct device *dev)
return -ENODEV; return -ENODEV;
} }
k_sleep(5); k_sleep(K_MSEC(5));
adxl362_get_reg(dev, &value, ADXL362_REG_PARTID, 1); adxl362_get_reg(dev, &value, ADXL362_REG_PARTID, 1);
if (value != ADXL362_PART_ID) { if (value != ADXL362_PART_ID) {

View file

@ -502,7 +502,7 @@ static int adxl372_reset(struct device *dev)
} }
/* Writing code 0x52 resets the device */ /* Writing code 0x52 resets the device */
ret = adxl372_reg_write(dev, ADXL372_RESET, ADXL372_RESET_CODE); ret = adxl372_reg_write(dev, ADXL372_RESET, ADXL372_RESET_CODE);
k_sleep(1000); k_sleep(K_MSEC(1000));
return ret; return ret;
} }

View file

@ -51,7 +51,7 @@ static int iaqcore_sample_fetch(struct device *dev, enum sensor_channel chan)
return 0; return 0;
} }
k_sleep(100); k_sleep(K_MSEC(100));
} }
if (drv_data->status == 0x01) { if (drv_data->status == 0x01) {

View file

@ -447,7 +447,7 @@ static int apds9960_init(struct device *dev)
struct apds9960_data *data = dev->driver_data; struct apds9960_data *data = dev->driver_data;
/* Initialize time 5.7ms */ /* Initialize time 5.7ms */
k_sleep(6); k_sleep(K_MSEC(6));
data->i2c = device_get_binding(config->i2c_name); data->i2c = device_get_binding(config->i2c_name);
if (data->i2c == NULL) { if (data->i2c == NULL) {

View file

@ -38,7 +38,7 @@ static int ccs811_sample_fetch(struct device *dev, enum sensor_channel chan)
break; break;
} }
k_sleep(100); k_sleep(K_MSEC(100));
} }
if (!(status & CCS811_STATUS_DATA_READY)) { if (!(status & CCS811_STATUS_DATA_READY)) {
@ -180,7 +180,7 @@ int ccs811_init(struct device *dev)
GPIO_DIR_OUT); GPIO_DIR_OUT);
gpio_pin_write(drv_data->gpio, CONFIG_CCS811_GPIO_RESET_PIN_NUM, 1); gpio_pin_write(drv_data->gpio, CONFIG_CCS811_GPIO_RESET_PIN_NUM, 1);
k_sleep(1); k_sleep(K_MSEC(1));
#endif #endif
/* /*
@ -192,7 +192,7 @@ int ccs811_init(struct device *dev)
GPIO_DIR_OUT); GPIO_DIR_OUT);
gpio_pin_write(drv_data->gpio, CONFIG_CCS811_GPIO_WAKEUP_PIN_NUM, 0); gpio_pin_write(drv_data->gpio, CONFIG_CCS811_GPIO_WAKEUP_PIN_NUM, 0);
k_sleep(1); k_sleep(K_MSEC(1));
#endif #endif
/* Switch device to application mode */ /* Switch device to application mode */

View file

@ -162,7 +162,7 @@ static int ens210_wait_boot(struct device *i2c_dev)
(u8_t *)&sys_stat); (u8_t *)&sys_stat);
if (ret < 0) { if (ret < 0) {
k_sleep(1); k_sleep(K_MSEC(1));
continue; continue;
} }
@ -176,7 +176,7 @@ static int ens210_wait_boot(struct device *i2c_dev)
ens210_sys_enable(i2c_dev); ens210_sys_enable(i2c_dev);
k_sleep(2); k_sleep(K_MSEC(2));
} }
if (ret < 0) { if (ret < 0) {

View file

@ -158,7 +158,7 @@ int hts221_init(struct device *dev)
* the device requires about 2.2 ms to download the flash content * the device requires about 2.2 ms to download the flash content
* into the volatile mem * into the volatile mem
*/ */
k_sleep(3); k_sleep(K_MSEC(3));
if (hts221_read_conversion_data(drv_data) < 0) { if (hts221_read_conversion_data(drv_data) < 0) {
LOG_ERR("Failed to read conversion data."); LOG_ERR("Failed to read conversion data.");

View file

@ -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, lsm6dsl_shub_write_slave_reg(data, i2c_addr,
LIS2MDL_CFG_REG_A, mag_cfg, 1); 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 */ /* configure mag */
mag_cfg[0] = LIS2MDL_ODR_10HZ; 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, lsm6dsl_shub_write_slave_reg(data, i2c_addr,
LPS22HB_CTRL_REG2, baro_cfg, 1); 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 */ /* configure device */
baro_cfg[0] = LPS22HB_ODR_10HZ | LPS22HB_LPF_EN | LPS22HB_BDU_EN; 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, LSM6DSL_MASK_FUNC_CFG_EN,
func_en << LSM6DSL_SHIFT_FUNC_CFG_EN); func_en << LSM6DSL_SHIFT_FUNC_CFG_EN);
k_sleep(1); k_sleep(K_MSEC(1));
} }
#ifdef LSM6DSL_DEBUG #ifdef LSM6DSL_DEBUG

View file

@ -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, lsm6dso_shub_write_slave_reg(data, i2c_addr,
LIS2MDL_CFG_REG_A, mag_cfg, 1); 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 */ /* configure mag */
mag_cfg[0] = LIS2MDL_ODR_10HZ; 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, lsm6dso_shub_write_slave_reg(data, i2c_addr,
LPS22HB_CTRL_REG2, baro_cfg, 1); 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 */ /* configure device */
baro_cfg[0] = LPS22HB_ODR_10HZ | LPS22HB_LPF_EN | LPS22HB_BDU_EN; 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, lsm6dso_shub_write_slave_reg(data, i2c_addr,
LPS22HH_CTRL_REG2, baro_cfg, 1); 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 */ /* configure device */
baro_cfg[0] = LPS22HH_IF_ADD_INC; baro_cfg[0] = LPS22HH_IF_ADD_INC;

View file

@ -224,7 +224,7 @@ static int vl53l0x_init(struct device *dev)
} }
gpio_pin_write(gpio, CONFIG_VL53L0X_XSHUT_GPIO_PIN_NUM, 1); gpio_pin_write(gpio, CONFIG_VL53L0X_XSHUT_GPIO_PIN_NUM, 1);
k_sleep(100); k_sleep(K_MSEC(100));
#endif #endif
drv_data->i2c = device_get_binding(DT_INST_0_ST_VL53L0X_BUS_NAME); drv_data->i2c = device_get_binding(DT_INST_0_ST_VL53L0X_BUS_NAME);

View file

@ -190,7 +190,7 @@ VL53L0X_Error VL53L0X_RdDWord(VL53L0X_DEV Dev, uint8_t index, uint32_t *data)
VL53L0X_Error VL53L0X_PollingDelay(VL53L0X_DEV Dev) VL53L0X_Error VL53L0X_PollingDelay(VL53L0X_DEV Dev)
{ {
k_sleep(2); k_sleep(K_MSEC(2));
return VL53L0X_ERROR_NONE; return VL53L0X_ERROR_NONE;
} }

View file

@ -318,7 +318,7 @@ void usbip_start(void)
if (connfd < 0) { if (connfd < 0) {
if (errno == EAGAIN || errno == EWOULDBLOCK) { if (errno == EAGAIN || errno == EWOULDBLOCK) {
/* Non-blocking accept */ /* Non-blocking accept */
k_sleep(100); k_sleep(K_MSEC(100));
continue; continue;
} }
@ -347,7 +347,7 @@ void usbip_start(void)
if (errno == EAGAIN || if (errno == EAGAIN ||
errno == EWOULDBLOCK) { errno == EWOULDBLOCK) {
/* Non-blocking accept */ /* Non-blocking accept */
k_sleep(100); k_sleep(K_MSEC(100));
continue; continue;
} }
@ -389,7 +389,7 @@ void usbip_start(void)
if (read < 0) { if (read < 0) {
if (errno == EAGAIN || errno == EWOULDBLOCK) { if (errno == EAGAIN || errno == EWOULDBLOCK) {
/* Non-blocking accept */ /* Non-blocking accept */
k_sleep(100); k_sleep(K_MSEC(100));
continue; continue;
} }

View file

@ -48,7 +48,7 @@ static int eswifi_spi_wait_cmddata_ready(struct eswifi_spi_data *spi)
do { do {
/* allow other threads to be scheduled */ /* allow other threads to be scheduled */
k_sleep(1); k_sleep(K_MSEC(1));
} while (!eswifi_spi_cmddata_ready(spi) && --max_retries); } while (!eswifi_spi_cmddata_ready(spi) && --max_retries);
return max_retries ? 0 : -ETIMEDOUT; return max_retries ? 0 : -ETIMEDOUT;
@ -169,7 +169,7 @@ data:
/* Flush remaining data if receiving buffer not large enough */ /* Flush remaining data if receiving buffer not large enough */
while (eswifi_spi_cmddata_ready(spi)) { while (eswifi_spi_cmddata_ready(spi)) {
eswifi_spi_read(eswifi, tmp, 2); 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 */ /* Our device is flagged with SPI_HOLD_ON_CS|SPI_LOCK_ON, release */

View file

@ -39,10 +39,10 @@ static struct eswifi_dev eswifi0; /* static instance */
static int eswifi_reset(struct eswifi_dev *eswifi) static int eswifi_reset(struct eswifi_dev *eswifi)
{ {
gpio_pin_write(eswifi->resetn.dev, eswifi->resetn.pin, 0); 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->resetn.dev, eswifi->resetn.pin, 1);
gpio_pin_write(eswifi->wakeup.dev, eswifi->wakeup.pin, 1); gpio_pin_write(eswifi->wakeup.dev, eswifi->wakeup.pin, 1);
k_sleep(500); k_sleep(K_MSEC(500));
/* fetch the cursor */ /* fetch the cursor */
return eswifi_request(eswifi, NULL, 0, eswifi->buf, return eswifi_request(eswifi, NULL, 0, eswifi->buf,

View file

@ -142,7 +142,7 @@ void main(void)
for (i = 0; i < 5; i++) { for (i = 0; i < 5; i++) {
gpio_pin_write(led1, DT_ALIAS_LED1_GPIOS_PIN, on); gpio_pin_write(led1, DT_ALIAS_LED1_GPIOS_PIN, on);
k_sleep(200); k_sleep(K_MSEC(200));
on = (on == 1) ? 0 : 1; on = (on == 1) ? 0 : 1;
} }
@ -350,7 +350,7 @@ void main(void)
#endif /* CONFIG_LSM6DSL */ #endif /* CONFIG_LSM6DSL */
printk("- (%d) (trig_cnt: %d)\n\n", ++cnt, lsm6dsl_trig_cnt); printk("- (%d) (trig_cnt: %d)\n\n", ++cnt, lsm6dsl_trig_cnt);
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -260,7 +260,7 @@ void main(void)
for (i = 0; i < 6; i++) { for (i = 0; i < 6; i++) {
gpio_pin_write(led0, DT_ALIAS_LED0_GPIOS_PIN, on); gpio_pin_write(led0, DT_ALIAS_LED0_GPIOS_PIN, on);
gpio_pin_write(led1, DT_ALIAS_LED1_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; on = (on == 1) ? 0 : 1;
} }
@ -441,7 +441,7 @@ void main(void)
printk("%d:: iis3dhhc trig %d\n", cnt, iis3dhhc_trig_cnt); printk("%d:: iis3dhhc trig %d\n", cnt, iis3dhhc_trig_cnt);
#endif #endif
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -83,7 +83,7 @@ void main(void)
cfb_framebuffer_finalize(dev); cfb_framebuffer_finalize(dev);
#if defined(CONFIG_ARCH_POSIX) #if defined(CONFIG_ARCH_POSIX)
k_sleep(100); k_sleep(K_MSEC(100));
#endif #endif
} }
} }

View file

@ -138,6 +138,6 @@ void main(void)
if (color > 2) { if (color > 2) {
color = 0; color = 0;
} }
k_sleep(500); k_sleep(K_MSEC(500));
} }
} }

View file

@ -167,6 +167,6 @@ void main(void)
break; break;
} }
++cnt; ++cnt;
k_sleep(100); k_sleep(K_MSEC(100));
} }
} }

View file

@ -50,6 +50,6 @@ void main(void)
printf("\n"); printf("\n");
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -222,7 +222,7 @@ void main(void)
{ {
int ret; int ret;
k_sleep(500); k_sleep(K_MSEC(500));
#ifdef CONFIG_ESPI_GPIO_DEV_NEEDED #ifdef CONFIG_ESPI_GPIO_DEV_NEEDED
gpio_dev0 = device_get_binding(CONFIG_ESPI_GPIO_DEV0); gpio_dev0 = device_get_binding(CONFIG_ESPI_GPIO_DEV0);

View file

@ -68,7 +68,7 @@ void main(void)
"one-by-one"); "one-by-one");
for (i = 0; i < 128; i++) { for (i = 0; i < 128; i++) {
led_on(led_dev, i); led_on(led_dev, i);
k_sleep(100); k_sleep(K_MSEC(100));
} }
for (i = 500; i <= 2000; i *= 2) { for (i = 500; i <= 2000; i *= 2) {
@ -81,7 +81,7 @@ void main(void)
for (i = 100; i >= 0; i -= 10) { for (i = 100; i >= 0; i -= 10) {
LOG_INF("Setting LED brightness to %d%%", i); LOG_INF("Setting LED brightness to %d%%", i);
led_set_brightness(led_dev, 0, 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"); LOG_INF("Turning all LEDs off and restoring 100%% brightness");

View file

@ -309,7 +309,7 @@ void _pi_lcd_write(struct device *gpio_dev, u8_t bits)
void pi_lcd_home(struct device *gpio_dev) void pi_lcd_home(struct device *gpio_dev)
{ {
_pi_lcd_command(gpio_dev, LCD_RETURN_HOME); _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 */ /** 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) void pi_lcd_clear(struct device *gpio_dev)
{ {
_pi_lcd_command(gpio_dev, LCD_CLEAR_DISPLAY); _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 * above 2.7V before sending commands. Arduino can turn on way
* before 4.5V so we'll wait 50 * before 4.5V so we'll wait 50
*/ */
k_sleep(50); k_sleep(K_MSEC(50));
/* this is according to the hitachi HD44780 datasheet /* this is according to the hitachi HD44780 datasheet
* figure 23/24, pg 45/46 try to set 4/8 bits mode * 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) { if (lcd_data.disp_func & LCD_8BIT_MODE) {
/* 1st try */ /* 1st try */
_pi_lcd_command(gpio_dev, 0x30); _pi_lcd_command(gpio_dev, 0x30);
k_sleep(5); /* wait for 5ms */ k_sleep(K_MSEC(5)); /* wait for 5ms */
/* 2nd try */ /* 2nd try */
_pi_lcd_command(gpio_dev, 0x30); _pi_lcd_command(gpio_dev, 0x30);
k_sleep(5); /* wait for 5ms */ k_sleep(K_MSEC(5)); /* wait for 5ms */
/* 3rd try */ /* 3rd try */
_pi_lcd_command(gpio_dev, 0x30); _pi_lcd_command(gpio_dev, 0x30);
k_sleep(1); /* wait for 1ms */ k_sleep(K_MSEC(1)); /* wait for 1ms */
/* Set 4bit interface */ /* Set 4bit interface */
_pi_lcd_command(gpio_dev, 0x30); _pi_lcd_command(gpio_dev, 0x30);
} else { } else {
/* 1st try */ /* 1st try */
_pi_lcd_command(gpio_dev, 0x03); _pi_lcd_command(gpio_dev, 0x03);
k_sleep(5); /* wait for 5ms */ k_sleep(K_MSEC(5)); /* wait for 5ms */
/* 2nd try */ /* 2nd try */
_pi_lcd_command(gpio_dev, 0x03); _pi_lcd_command(gpio_dev, 0x03);
k_sleep(5); /* wait for 5ms */ k_sleep(K_MSEC(5)); /* wait for 5ms */
/* 3rd try */ /* 3rd try */
_pi_lcd_command(gpio_dev, 0x03); _pi_lcd_command(gpio_dev, 0x03);
k_sleep(1); /* wait for 1ms */ k_sleep(K_MSEC(1)); /* wait for 1ms */
/* Set 4bit interface */ /* Set 4bit interface */
_pi_lcd_command(gpio_dev, 0x02); _pi_lcd_command(gpio_dev, 0x02);

View file

@ -40,7 +40,7 @@ static void saturate_ps2(struct k_timer *timer)
LOG_DBG("block host\n"); LOG_DBG("block host\n");
host_blocked = true; host_blocked = true;
ps2_disable_callback(ps2_0_dev); ps2_disable_callback(ps2_0_dev);
k_sleep(500); k_sleep(K_MSEC(500));
host_blocked = false; host_blocked = false;
ps2_enable_callback(ps2_0_dev); ps2_enable_callback(ps2_0_dev);
} }

View file

@ -86,7 +86,7 @@ void main(void)
for (int i = 0; i < WDT_FEED_TRIES; ++i) { for (int i = 0; i < WDT_FEED_TRIES; ++i) {
printk("Feeding watchdog...\n"); printk("Feeding watchdog...\n");
wdt_feed(wdt, wdt_channel_id); wdt_feed(wdt, wdt_channel_id);
k_sleep(50); k_sleep(K_MSEC(50));
} }
/* Waiting for the SoC reset. */ /* Waiting for the SoC reset. */

View file

@ -45,7 +45,7 @@ void main(void)
lv_label_set_text(count_label, count_str); lv_label_set_text(count_label, count_str);
} }
lv_task_handler(); lv_task_handler();
k_sleep(10); k_sleep(K_MSEC(10));
++count; ++count;
} }
} }

View file

@ -463,6 +463,6 @@ void main(void)
while (1) { while (1) {
publisher(); publisher();
k_sleep(5000); k_sleep(K_MSEC(5000));
} }
} }

View file

@ -258,6 +258,6 @@ void main(void)
/* Wait a few seconds before main() exit, giving the sample the /* Wait a few seconds before main() exit, giving the sample the
* opportunity to dump some output before coverage data gets emitted * opportunity to dump some output before coverage data gets emitted
*/ */
k_sleep(5000); k_sleep(K_MSEC(5000));
#endif #endif
} }

View file

@ -257,6 +257,6 @@ void main(void)
/* Wait a few seconds before main() exit, giving the sample the /* Wait a few seconds before main() exit, giving the sample the
* opportunity to dump some output before coverage data gets emitted * opportunity to dump some output before coverage data gets emitted
*/ */
k_sleep(5000); k_sleep(K_MSEC(5000));
#endif #endif
} }

View file

@ -84,7 +84,7 @@ static void process(struct device *dev)
sensor_value_to_double(&temp_val)); sensor_value_to_double(&temp_val));
if (!IS_ENABLED(CONFIG_ADT7420_TRIGGER)) { if (!IS_ENABLED(CONFIG_ADT7420_TRIGGER)) {
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }
} }

View file

@ -58,7 +58,7 @@ void main(void)
if (IS_ENABLED(CONFIG_ADXL362_TRIGGER)) { if (IS_ENABLED(CONFIG_ADXL362_TRIGGER)) {
k_sem_take(&sem, K_FOREVER); k_sem_take(&sem, K_FOREVER);
} else { } else {
k_sleep(1000); k_sleep(K_MSEC(1000));
if (sensor_sample_fetch(dev) < 0) { if (sensor_sample_fetch(dev) < 0) {
printf("Sample fetch error\n"); printf("Sample fetch error\n");
return; return;

View file

@ -104,7 +104,7 @@ void main(void)
} }
if (!IS_ENABLED(CONFIG_ADXL372_TRIGGER)) { if (!IS_ENABLED(CONFIG_ADXL372_TRIGGER)) {
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }
} }

View file

@ -105,6 +105,6 @@ void main(void)
printk("new sample:\n"); printk("new sample:\n");
print_buffer(temp_value, ARRAY_SIZE(temp_value)); print_buffer(temp_value, ARRAY_SIZE(temp_value));
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -30,6 +30,6 @@ void main(void)
co2.val1, co2.val2, co2.val1, co2.val2,
voc.val1, voc.val2); voc.val1, voc.val2);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -63,7 +63,7 @@ void main(void)
printk("Waiting for a threshold event\n"); printk("Waiting for a threshold event\n");
k_sem_take(&sem, K_FOREVER); k_sem_take(&sem, K_FOREVER);
#else #else
k_sleep(5000); k_sleep(K_MSEC(5000));
#endif #endif
if (sensor_sample_fetch(dev)) { if (sensor_sample_fetch(dev)) {
printk("sensor_sample fetch failed\n"); printk("sensor_sample fetch failed\n");
@ -81,7 +81,7 @@ void main(void)
p_state = DEVICE_PM_LOW_POWER_STATE; p_state = DEVICE_PM_LOW_POWER_STATE;
device_set_power_state(dev, p_state, NULL, NULL); device_set_power_state(dev, p_state, NULL, NULL);
printk("set low power state for 2s\n"); printk("set low power state for 2s\n");
k_sleep(2000); k_sleep(K_MSEC(2000));
p_state = DEVICE_PM_ACTIVE_STATE; p_state = DEVICE_PM_ACTIVE_STATE;
device_set_power_state(dev, p_state, NULL, NULL); device_set_power_state(dev, p_state, NULL, NULL);
#endif #endif

View file

@ -31,6 +31,6 @@ void main(void)
temp.val1, temp.val2, press.val1, press.val2, temp.val1, temp.val2, press.val1, press.val2,
humidity.val1, humidity.val2); humidity.val1, humidity.val2);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -17,7 +17,7 @@ void main(void)
printf("Device %p name is %s\n", dev, dev->config->name); printf("Device %p name is %s\n", dev, dev->config->name);
while (1) { while (1) {
k_sleep(3000); k_sleep(K_MSEC(3000));
sensor_sample_fetch(dev); sensor_sample_fetch(dev);
sensor_channel_get(dev, SENSOR_CHAN_AMBIENT_TEMP, &temp); sensor_channel_get(dev, SENSOR_CHAN_AMBIENT_TEMP, &temp);

View file

@ -31,7 +31,7 @@ void do_main(struct device *dev)
sensor_value_to_double(&y), sensor_value_to_double(&y),
sensor_value_to_double(&z)); sensor_value_to_double(&z));
k_sleep(500); k_sleep(K_MSEC(500));
} }
} }

View file

@ -25,7 +25,7 @@ static void do_main(struct device *dev)
printk("Voltage: %d.%06dV; Current: %d.%06dA\n\n", voltage.val1, printk("Voltage: %d.%06dV; Current: %d.%06dA\n\n", voltage.val1,
voltage.val2, current.val1, current.val2); voltage.val2, current.val1, current.val2);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -30,6 +30,6 @@ void main(void)
temperature.val1, temperature.val2, temperature.val1, temperature.val2,
humidity.val1, humidity.val2); humidity.val1, humidity.val2);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -68,7 +68,7 @@ void main(void)
while (!IS_ENABLED(CONFIG_HTS221_TRIGGER)) { while (!IS_ENABLED(CONFIG_HTS221_TRIGGER)) {
process_sample(dev); process_sample(dev);
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
k_sleep(K_FOREVER); k_sleep(K_FOREVER);
} }

View file

@ -65,6 +65,6 @@ void main(void)
printf("Failed to read accelerometer data\n"); printf("Failed to read accelerometer data\n");
} }
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -174,6 +174,6 @@ void main(void)
printk("- (%d) (trig_cnt: %d)\n\n", ++cnt, lsm6dsl_trig_cnt); printk("- (%d) (trig_cnt: %d)\n\n", ++cnt, lsm6dsl_trig_cnt);
print_samples = 1; print_samples = 1;
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -30,7 +30,7 @@ static void do_main(struct device *dev)
sensor_value_to_double(&value_y), sensor_value_to_double(&value_y),
sensor_value_to_double(&value_z)); sensor_value_to_double(&value_z));
k_sleep(500); k_sleep(K_MSEC(500));
} }
} }

View file

@ -25,6 +25,6 @@ void main(void)
/* Print green LED data*/ /* Print green LED data*/
printf("GREEN=%d\n", green.val1); printf("GREEN=%d\n", green.val1);
k_sleep(20); k_sleep(K_MSEC(20));
} }
} }

View file

@ -43,6 +43,6 @@ void main(void)
lum = val.val1; lum = val.val1;
printk("sensor: lum reading: %d\n", lum); printk("sensor: lum reading: %d\n", lum);
k_sleep(4000); k_sleep(K_MSEC(4000));
} }
} }

View file

@ -72,6 +72,6 @@ void main(void)
printf("temp: %d.%06d\n", temp.val1, temp.val2); printf("temp: %d.%06d\n", temp.val1, temp.val2);
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -41,6 +41,6 @@ void main(void)
printf("Temperature: %d.%06d, Pressure: %d.%06d\n", temp.val1, printf("Temperature: %d.%06d, Pressure: %d.%06d\n", temp.val1,
temp.val2, press.val1, press.val2); temp.val2, press.val1, press.val2);
k_sleep(10000); k_sleep(K_MSEC(10000));
} }
} }

View file

@ -84,6 +84,6 @@ void main(void)
sensor_value_to_double(&temp), sensor_value_to_double(&temp),
sensor_value_to_double(&hum)); sensor_value_to_double(&hum));
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -44,7 +44,7 @@ void do_main(struct device *dev)
setup_trigger(dev); setup_trigger(dev);
while (1) { 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); ret = sensor_channel_get(dev, SENSOR_CHAN_PROX, &prox_value);
printk("prox is %d\n", prox_value.val1); printk("prox is %d\n", prox_value.val1);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -101,6 +101,6 @@ void main(void)
#endif #endif
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -43,6 +43,6 @@ void main(void)
printf("Temperature is %gC\n", printf("Temperature is %gC\n",
sensor_value_to_double(&temp_value)); sensor_value_to_double(&temp_value));
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -50,7 +50,7 @@ static void do_main(struct device *dev)
printk("temp is %d (%d micro)\n", temp_value.val1, printk("temp is %d (%d micro)\n", temp_value.val1,
temp_value.val2); temp_value.val2);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -37,6 +37,6 @@ void main(void)
printk("temp is %d.%d oC\n", temp_value.val1, temp_value.val2); printk("temp is %d.%d oC\n", temp_value.val1, temp_value.val2);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -36,6 +36,6 @@ void main(void)
&value); &value);
printf("distance is %.3fm\n", sensor_value_to_double(&value)); printf("distance is %.3fm\n", sensor_value_to_double(&value));
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -98,6 +98,6 @@ void main(void)
sensor_value_to_double(&accel_xyz[1]), sensor_value_to_double(&accel_xyz[1]),
sensor_value_to_double(&accel_xyz[2])); sensor_value_to_double(&accel_xyz[2]));
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -146,6 +146,6 @@ void main(void)
sensor_value_to_double(&magn[1]), sensor_value_to_double(&magn[1]),
sensor_value_to_double(&magn[2])); sensor_value_to_double(&magn[2]));
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -290,6 +290,6 @@ void main(void)
#endif #endif
cnt++; cnt++;
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -421,6 +421,6 @@ void main(void)
#endif #endif
cnt++; cnt++;
k_sleep(2000); k_sleep(K_MSEC(2000));
} }
} }

View file

@ -74,7 +74,7 @@ void main(void)
} }
while (1) { while (1) {
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
} }

View file

@ -243,7 +243,7 @@ static void external_log_system_showcase(void)
static void wait_on_log_flushed(void) static void wait_on_log_flushed(void)
{ {
while (log_buffered_cnt()) { 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(); bool usermode = _is_user_context();
k_sleep(100); k_sleep(K_MSEC(100));
printk("\n\t---=< RUNNING LOGGER DEMO FROM %s THREAD >=---\n\n", printk("\n\t---=< RUNNING LOGGER DEMO FROM %s THREAD >=---\n\n",
(usermode) ? "USER" : "KERNEL"); (usermode) ? "USER" : "KERNEL");

View file

@ -167,7 +167,7 @@ void main(void)
* main thread idle while the mcumgr server runs. * main thread idle while the mcumgr server runs.
*/ */
while (1) { while (1) {
k_sleep(1000); k_sleep(K_MSEC(1000));
STATS_INC(smp_svr_stats, ticks); STATS_INC(smp_svr_stats, ticks);
} }
} }

View file

@ -91,7 +91,7 @@ void main(void)
break; break;
} else { } else {
/* Give CPU resources to low priority threads. */ /* Give CPU resources to low priority threads. */
k_sleep(100); k_sleep(K_MSEC(100));
} }
} }

View file

@ -136,7 +136,7 @@ void main(void)
break; break;
} }
k_sleep(100); k_sleep(K_MSEC(100));
} }
while (1) { while (1) {
@ -145,7 +145,7 @@ void main(void)
break; break;
} }
k_sleep(100); k_sleep(K_MSEC(100));
} }
LOG_INF("DTR set, start test"); LOG_INF("DTR set, start test");

View file

@ -207,7 +207,7 @@ void enc(void)
} }
/* test for CT flag */ /* test for CT flag */
while (fBUFOUT != 0) { while (fBUFOUT != 0) {
k_sleep(100); k_sleep(K_MSEC(100));
} }
/* ct thread has cleared the buffer */ /* ct thread has cleared the buffer */
memcpy(&BUFOUT, &enc_ct, SAMP_BLOCKSIZE); memcpy(&BUFOUT, &enc_ct, SAMP_BLOCKSIZE);
@ -226,7 +226,7 @@ void enc(void)
void pt(void) void pt(void)
{ {
k_sleep(2000); k_sleep(K_MSEC(2000));
while (1) { while (1) {
k_sem_take(&allforone, K_FOREVER); k_sem_take(&allforone, K_FOREVER);
if (fBUFIN == 0) { /* send message to encode */ if (fBUFIN == 0) { /* send message to encode */
@ -245,7 +245,7 @@ void pt(void)
fBUFIN = 1; fBUFIN = 1;
} }
k_sem_give(&allforone); k_sem_give(&allforone);
k_sleep(5000); k_sleep(K_MSEC(5000));
} }
} }

View file

@ -194,7 +194,7 @@ static ssize_t tty_read_unbuf(struct tty_serial *tty, void *buf, size_t size)
* of data without extra delays. * of data without extra delays.
*/ */
if (res == -1) { if (res == -1) {
k_sleep(1); k_sleep(K_MSEC(1));
} }
} }

View file

@ -23,7 +23,7 @@
#endif #endif
#define TICK_SYNCH() k_sleep(1) #define TICK_SYNCH() k_sleep(K_MSEC(1))
#define OS_GET_TIME() k_cycle_get_32() #define OS_GET_TIME() k_cycle_get_32()

View file

@ -55,7 +55,7 @@ void test_arm_runtime_nmi(void)
for (i = 0U; i < 10; i++) { for (i = 0U; i < 10; i++) {
printk("Trigger NMI in 10s: %d s\n", i); printk("Trigger NMI in 10s: %d s\n", i);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
/* Trigger NMI: Should fire immediately */ /* Trigger NMI: Should fire immediately */

View file

@ -31,7 +31,7 @@ void main(void)
/* /*
* Go to sleep for 1 tick in order to timestamp when idle thread halts. * 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; int freq = sys_clock_hw_cycles_per_sec() / 1000000;

View file

@ -108,7 +108,7 @@ void main(void)
partner_prio, 0, 0); partner_prio, 0, 0);
/* Let it start running and pend */ /* Let it start running and pend */
k_sleep(100); k_sleep(K_MSEC(100));
u64_t tot = 0U; u64_t tot = 0U;
u32_t runs = 0U; u32_t runs = 0U;

View file

@ -149,7 +149,7 @@ void main(void)
*/ */
u64_t time_stamp = z_tick_get(); u64_t time_stamp = z_tick_get();
k_sleep(1); k_sleep(K_MSEC(1));
u64_t time_stamp_2 = z_tick_get(); u64_t time_stamp_2 = z_tick_get();

View file

@ -159,7 +159,7 @@ void msg_passing_bench(void)
thread_consumer_get_msgq_w_cxt_switch, thread_consumer_get_msgq_w_cxt_switch,
NULL, NULL, NULL, NULL, NULL, NULL,
2 /*priority*/, 0, 50); 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); k_thread_abort(producer_get_w_cxt_switch_tid);
__msg_q_get_w_cxt_end_time = (z_arch_timing_value_swap_common); __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, thread_mbox_sync_put_receive,
NULL, NULL, NULL, NULL, NULL, NULL,
1 /*priority*/, 0, 0); 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); mbox_sync_put_end_time = (z_arch_timing_value_swap_common);
/*******************************************************************/ /*******************************************************************/
@ -212,7 +212,7 @@ void msg_passing_bench(void)
STACK_SIZE, STACK_SIZE,
thread_mbox_sync_get_receive, NULL, thread_mbox_sync_get_receive, NULL,
NULL, NULL, 2 /*priority*/, 0, 0); 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); 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, thread_mbox_async_put_receive,
NULL, NULL, NULL, NULL, NULL, NULL,
3 /*priority*/, 0, 0); 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; int single_element_buffer = 0, status;

View file

@ -60,7 +60,7 @@ void semaphore_bench(void)
NULL, NULL, NULL, NULL, NULL, NULL,
2 /*priority*/, 0, 0); 2 /*priority*/, 0, 0);
k_sleep(1000); k_sleep(K_MSEC(1000));
/* u64_t test_time1 = z_tsc_read(); */ /* u64_t test_time1 = z_tsc_read(); */
@ -76,7 +76,7 @@ void semaphore_bench(void)
NULL, NULL, NULL, NULL, NULL, NULL,
2 /*priority*/, 0, 0); 2 /*priority*/, 0, 0);
k_sleep(1000); k_sleep(K_MSEC(1000));
sem_give_end_time = (z_arch_timing_value_swap_common); sem_give_end_time = (z_arch_timing_value_swap_common);
u32_t sem_give_cycles = sem_give_end_time - sem_give_start_time; u32_t sem_give_cycles = sem_give_end_time - sem_give_start_time;

View file

@ -141,7 +141,7 @@ void system_thread_bench(void)
NULL, NULL, NULL, NULL, NULL, NULL,
-1 /*priority*/, 0, 0); -1 /*priority*/, 0, 0);
k_sleep(1); k_sleep(K_MSEC(1));
thread_abort_end_time = (z_arch_timing_value_swap_common); thread_abort_end_time = (z_arch_timing_value_swap_common);
z_arch_timing_swap_end = 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) #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_malloc = 0U;
u32_t sum_free = 0U; u32_t sum_free = 0U;
k_sleep(10); k_sleep(K_MSEC(10));
while (count++ != 100) { while (count++ != 100) {
TIMING_INFO_PRE_READ(); TIMING_INFO_PRE_READ();
heap_malloc_start_time = TIMING_INFO_OS_GET_TIME(); heap_malloc_start_time = TIMING_INFO_OS_GET_TIME();

View file

@ -34,7 +34,7 @@ k_tid_t yield1_tid;
void yield_bench(void) void yield_bench(void)
{ {
/* Thread yield*/ /* Thread yield*/
k_sleep(10); k_sleep(K_MSEC(10));
yield0_tid = k_thread_create(&my_thread, my_stack_area, yield0_tid = k_thread_create(&my_thread, my_stack_area,
STACK_SIZE, STACK_SIZE,
thread_yield0_test, thread_yield0_test,
@ -52,7 +52,7 @@ void yield_bench(void)
TIMING_INFO_PRE_READ(); TIMING_INFO_PRE_READ();
thread_sleep_start_time = TIMING_INFO_OS_GET_TIME(); 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); thread_sleep_end_time = ((u32_t)z_arch_timing_value_swap_common);
u32_t yield_cycles = (thread_end_time - thread_start_time) / 2000U; u32_t yield_cycles = (thread_end_time - thread_start_time) / 2000U;

View file

@ -223,7 +223,7 @@ static void connected(struct bt_conn *conn, u8_t conn_err)
} }
if (encrypt_link) { if (encrypt_link) {
k_sleep(500); k_sleep(K_MSEC(500));
bt_conn_auth_cb_register(&auth_cb_success); bt_conn_auth_cb_register(&auth_cb_success);
err = bt_conn_set_security(conn, BT_SECURITY_L2); err = bt_conn_set_security(conn, BT_SECURITY_L2);
if (err) { if (err) {

View file

@ -36,7 +36,7 @@ static void test_empty_thread(void *p1, void *p2, void *p3)
while (1) { while (1) {
printk("A silly demo thread. Iteration %i\n", i++); printk("A silly demo thread. Iteration %i\n", i++);
k_sleep(100); k_sleep(K_MSEC(100));
} }
} }

View file

@ -64,6 +64,6 @@ NATIVE_TASK(test_hook7, ON_EXIT, 310);
void main(void) void main(void)
{ {
k_sleep(100); k_sleep(K_MSEC(100));
posix_exit(0); posix_exit(0);
} }

View file

@ -66,7 +66,7 @@ static void test_all_instances(test_func_t func,
func(devices[i].name, devices[i].startup_us); func(devices[i].name, devices[i].startup_us);
tear_down_instance(devices[i].name); tear_down_instance(devices[i].name);
/* Allow logs to be printed. */ /* Allow logs to be printed. */
k_sleep(100); k_sleep(K_MSEC(100));
} }
} }
} }

View file

@ -120,7 +120,7 @@ static void test_all_instances(counter_test_func_t func,
} }
counter_tear_down_instance(devices[i]); counter_tear_down_instance(devices[i]);
/* Allow logs to be printed. */ /* Allow logs to be printed. */
k_sleep(100); k_sleep(K_MSEC(100));
} }
} }

View file

@ -78,7 +78,7 @@ static int test_task(u32_t chan_id, u32_t blen)
TC_PRINT("ERROR: transfer\n"); TC_PRINT("ERROR: transfer\n");
return TC_FAIL; return TC_FAIL;
} }
k_sleep(2000); k_sleep(K_MSEC(2000));
TC_PRINT("%s\n", rx_data); TC_PRINT("%s\n", rx_data);
if (strcmp(tx_data, rx_data) != 0) if (strcmp(tx_data, rx_data) != 0)
return TC_FAIL; return TC_FAIL;

View file

@ -65,7 +65,7 @@ static void init_callback(struct device *dev,
static void trigger_callback(struct device *dev, int enable_cb) static void trigger_callback(struct device *dev, int enable_cb)
{ {
gpio_pin_write(dev, PIN_OUT, 0); gpio_pin_write(dev, PIN_OUT, 0);
k_sleep(100); k_sleep(K_MSEC(100));
cb_cnt[0] = 0; cb_cnt[0] = 0;
cb_cnt[1] = 0; cb_cnt[1] = 0;
@ -74,9 +74,9 @@ static void trigger_callback(struct device *dev, int enable_cb)
} else { } else {
gpio_pin_disable_callback(dev, PIN_IN); gpio_pin_disable_callback(dev, PIN_IN);
} }
k_sleep(100); k_sleep(K_MSEC(100));
gpio_pin_write(dev, PIN_OUT, 1); gpio_pin_write(dev, PIN_OUT, 1);
k_sleep(1000); k_sleep(K_MSEC(1000));
} }
static int test_callback_add_remove(void) 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); init_callback(dev, callback_1, callback_remove_self);
gpio_pin_write(dev, PIN_OUT, 0); gpio_pin_write(dev, PIN_OUT, 0);
k_sleep(100); k_sleep(K_MSEC(100));
cb_data[0].aux = INT_MAX; cb_data[0].aux = INT_MAX;
cb_data[1].aux = INT_MAX; cb_data[1].aux = INT_MAX;

View file

@ -79,9 +79,9 @@ static int test_callback(int mode)
/* 3. enable callback, trigger PIN_IN interrupt by operate PIN_OUT */ /* 3. enable callback, trigger PIN_IN interrupt by operate PIN_OUT */
cb_cnt = 0; cb_cnt = 0;
gpio_pin_enable_callback(dev, PIN_IN); 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); 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 =*/ /*= checkpoint: check callback is triggered =*/
TC_PRINT("check enabled callback\n"); TC_PRINT("check enabled callback\n");

View file

@ -35,7 +35,7 @@ void test_gpio_pin_read_write(void)
zassert_true(gpio_pin_write(dev, PIN_OUT, val_write) == 0, zassert_true(gpio_pin_write(dev, PIN_OUT, val_write) == 0,
"write data fail"); "write data fail");
TC_PRINT("write: %" PRIu32 "\n", val_write); 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, zassert_true(gpio_pin_read(dev, PIN_IN, &val_read) == 0,
"read data fail"); "read data fail");
TC_PRINT("read: %" PRIu32 "\n", val_read); TC_PRINT("read: %" PRIu32 "\n", val_read);

View file

@ -60,7 +60,7 @@ static int test_gy271(void)
return TC_FAIL; return TC_FAIL;
} }
k_sleep(1); k_sleep(K_MSEC(1));
datas[0] = 0x03; datas[0] = 0x03;
if (i2c_write(i2c_dev, datas, 1, 0x1E)) { if (i2c_write(i2c_dev, datas, 1, 0x1E)) {
@ -110,7 +110,7 @@ static int test_burst_gy271(void)
return TC_FAIL; return TC_FAIL;
} }
k_sleep(1); k_sleep(K_MSEC(1));
(void)memset(datas, 0, sizeof(datas)); (void)memset(datas, 0, sizeof(datas));

View file

@ -426,7 +426,7 @@ void test_i2s_transfer_rx_overrun(void)
ret = rx_block_read(dev_i2s, 0); ret = rx_block_read(dev_i2s, 0);
zassert_equal(ret, TC_PASS, NULL); zassert_equal(ret, TC_PASS, NULL);
k_sleep(200); k_sleep(K_MSEC(200));
} }
/** @brief TX buffer underrun. /** @brief TX buffer underrun.
@ -463,7 +463,7 @@ void test_i2s_transfer_tx_underrun(void)
ret = rx_block_read(dev_i2s, 0); ret = rx_block_read(dev_i2s, 0);
zassert_equal(ret, TC_PASS, NULL); zassert_equal(ret, TC_PASS, NULL);
k_sleep(200); k_sleep(K_MSEC(200));
/* Write one more TX data block, expect an error */ /* Write one more TX data block, expect an error */
ret = tx_block_write(dev_i2s, 2, -EIO); 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); ret = i2s_trigger(dev_i2s, I2S_DIR_TX, I2S_TRIGGER_PREPARE);
zassert_equal(ret, 0, "TX PREPARE trigger failed"); zassert_equal(ret, 0, "TX PREPARE trigger failed");
k_sleep(200); k_sleep(K_MSEC(200));
/* Transmit and receive two more data blocks */ /* Transmit and receive two more data blocks */
ret = tx_block_write(dev_i2s, 1, 0); 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); ret = rx_block_read(dev_i2s, 1);
zassert_equal(ret, TC_PASS, NULL); zassert_equal(ret, TC_PASS, NULL);
k_sleep(200); k_sleep(K_MSEC(200));
} }

Some files were not shown because too many files have changed in this diff Show more