From 5b9dea56045b742fc04b96223a340c51f4adae56 Mon Sep 17 00:00:00 2001 From: Julian Oes <julian@oes.ch> Date: Thu, 4 Oct 2018 06:51:04 +0200 Subject: [PATCH] Replacing usleep with px4_usleep This is a step towards isolating time from the system. --- boards/px4/fmu-v2/src/init.c | 4 +-- boards/px4/fmu-v2/src/spi.c | 5 +-- platforms/posix/src/main.cpp | 4 +-- src/drivers/barometer/ms5611/ms5611.cpp | 8 ++--- src/drivers/barometer/ms5611/ms5611_i2c.cpp | 3 +- src/drivers/barometer/ms5611/ms5611_spi.cpp | 3 +- src/drivers/batt_smbus/batt_smbus.cpp | 8 ++--- .../differential_pressure/ms5525/MS5525.cpp | 2 +- .../differential_pressure/sdp3x/SDP3X.cpp | 4 +-- .../distance_sensor/leddar_one/leddar_one.cpp | 2 +- .../distance_sensor/ll40ls/LidarLiteI2C.cpp | 8 ++--- src/drivers/distance_sensor/mb12xx/mb12xx.cpp | 4 +-- src/drivers/distance_sensor/pga460/pga460.cpp | 36 +++++++++---------- src/drivers/distance_sensor/sf0x/sf0x.cpp | 2 +- src/drivers/distance_sensor/sf1xx/sf1xx.cpp | 2 +- src/drivers/distance_sensor/srf02/srf02.cpp | 4 +-- .../distance_sensor/teraranger/teraranger.cpp | 2 +- src/drivers/distance_sensor/tfmini/tfmini.cpp | 2 +- .../distance_sensor/ulanding/ulanding.cpp | 4 +-- src/drivers/gps/devices | 2 +- src/drivers/gps/gps.cpp | 16 ++++----- src/drivers/imu/mpu6000/mpu6000.cpp | 19 +++++----- src/drivers/imu/mpu9250/mag.cpp | 7 ++-- src/drivers/imu/mpu9250/mpu9250.cpp | 3 +- src/drivers/lights/rgbled/rgbled.cpp | 2 +- src/drivers/magnetometer/hmc5883/hmc5883.cpp | 3 +- src/drivers/magnetometer/lis3mdl/lis3mdl.cpp | 9 ++--- src/drivers/pwm_input/pwm_input.cpp | 3 +- src/drivers/px4flow/px4flow.cpp | 2 +- src/drivers/px4io/px4io.cpp | 24 ++++++------- src/drivers/px4io/px4io_uploader.cpp | 3 +- src/drivers/stm32/adc/adc.cpp | 10 +++--- src/drivers/stm32/tone_alarm/tone_alarm.cpp | 2 +- src/drivers/tone_alarm_sim/tone_alarm.cpp | 2 +- src/examples/bottle_drop/bottle_drop.cpp | 12 +++---- .../px4_mavlink_debug/px4_mavlink_debug.cpp | 2 +- src/include/visibility.h | 11 ++++++ src/lib/cdev/posix/cdev_platform.cpp | 2 +- src/lib/cdev/test/cdevtest_example.cpp | 2 +- src/lib/parameters/parameters.cpp | 2 +- src/lib/rc/dsm.cpp | 2 +- .../attitude_estimator_q_main.cpp | 4 +-- .../camera_feedback/camera_feedback.cpp | 2 +- src/modules/commander/Commander.cpp | 20 +++++------ .../commander/accelerometer_calibration.cpp | 4 +-- .../commander/airspeed_calibration.cpp | 6 ++-- src/modules/commander/arm_auth.cpp | 2 +- .../commander/calibration_routines.cpp | 20 +++++------ src/modules/commander/calibration_routines.h | 6 ++-- src/modules/commander/esc_calibration.cpp | 4 +-- src/modules/commander/gyro_calibration.cpp | 4 +-- src/modules/commander/mag_calibration.cpp | 18 +++++----- src/modules/commander/rc_calibration.cpp | 2 +- src/modules/commander/rc_check.cpp | 20 +++++------ src/modules/ekf2/ekf2_main.cpp | 2 +- .../events/temperature_calibration/task.cpp | 4 +-- .../GroundRoverAttitudeControl.cpp | 4 +-- .../GroundRoverPositionControl.cpp | 4 +-- .../landing_target_estimator_main.cpp | 2 +- src/modules/logger/log_writer_file.cpp | 4 +-- src/modules/mavlink/mavlink_main.cpp | 28 +++++++-------- src/modules/mavlink/mavlink_receiver.cpp | 4 +-- .../mc_att_control/mc_att_control_main.cpp | 2 +- src/modules/navigator/navigator_main.cpp | 2 +- src/modules/replay/replay_main.cpp | 4 +-- src/modules/sensors/sensors.cpp | 2 +- .../simulator/airspeedsim/airspeedsim.cpp | 2 +- src/modules/simulator/gpssim/gpssim.cpp | 6 ++-- src/modules/simulator/simulator.cpp | 2 +- src/modules/simulator/simulator_mavlink.cpp | 4 +-- src/modules/uORB/uORBDeviceMaster.cpp | 2 +- src/modules/uORB/uORBDeviceNode.cpp | 2 +- .../uORB/uORB_tests/uORBTest_UnitTest.cpp | 16 ++++----- .../uORB/uORB_tests/uORBTest_UnitTest.hpp | 2 +- src/modules/vmount/vmount.cpp | 6 ++-- .../vtol_att_control_main.cpp | 4 +-- src/platforms/apps.cpp.in | 3 +- src/platforms/common/work_queue/hrt_thread.c | 2 +- src/platforms/common/work_queue/work_thread.c | 2 +- src/platforms/px4_module.h | 5 +-- src/platforms/px4_nodehandle.h | 3 +- src/platforms/px4_time.h | 2 ++ src/systemcmds/bl_update/bl_update.c | 4 +-- src/systemcmds/esc_calib/esc_calib.c | 8 ++--- src/systemcmds/led_control/led_control.cpp | 14 ++++---- src/systemcmds/mixer/mixer.cpp | 2 +- src/systemcmds/motor_ramp/motor_ramp.cpp | 4 +-- src/systemcmds/mtd/24xxxx_mtd.c | 7 ++-- src/systemcmds/pwm/pwm.cpp | 8 ++--- src/systemcmds/reboot/reboot.c | 2 +- src/systemcmds/tests/hrt_test/hrt_test.cpp | 2 +- src/systemcmds/tests/test_adc.c | 3 +- src/systemcmds/tests/test_dataman.c | 2 +- src/systemcmds/tests/test_hott_telemetry.c | 5 +-- src/systemcmds/tests/test_hrt.cpp | 6 ++-- src/systemcmds/tests/test_hysteresis.cpp | 34 +++++++++--------- src/systemcmds/tests/test_led.c | 3 +- src/systemcmds/tests/test_microbench_hrt.cpp | 2 +- src/systemcmds/tests/test_microbench_math.cpp | 2 +- .../tests/test_microbench_matrix.cpp | 2 +- src/systemcmds/tests/test_microbench_uorb.cpp | 2 +- src/systemcmds/tests/test_mixer.cpp | 6 ++-- src/systemcmds/tests/test_mount.c | 10 +++--- src/systemcmds/tests/test_ppm_loopback.c | 3 +- src/systemcmds/tests/test_rc.c | 2 +- src/systemcmds/tests/test_sensors.c | 9 ++--- src/systemcmds/tests/test_servo.c | 3 +- src/systemcmds/tests/test_sleep.c | 3 +- src/systemcmds/top/top.c | 2 +- .../topic_listener/listener_main.cpp | 2 +- src/systemcmds/tune_control/tune_control.cpp | 6 ++-- src/templates/module/module.cpp | 2 +- 112 files changed, 339 insertions(+), 305 deletions(-) diff --git a/boards/px4/fmu-v2/src/init.c b/boards/px4/fmu-v2/src/init.c index 49c37cc398..b4b6044ee5 100644 --- a/boards/px4/fmu-v2/src/init.c +++ b/boards/px4/fmu-v2/src/init.c @@ -133,7 +133,7 @@ __EXPORT void board_peripheral_reset(int ms) stm32_gpiowrite(GPIO_VDD_5V_PERIPH_EN, 1); /* wait for the peripheral rail to reach GND */ - usleep(ms * 1000); + px4_usleep(ms * 1000); warnx("reset done, %d ms", ms); /* re-enable power */ @@ -393,7 +393,7 @@ __EXPORT int board_app_initialize(uintptr_t arg) #endif /* Ensure the power is on 1 ms before we drive the GPIO pins */ - usleep(1000); + px4_usleep(1000); if (OK == determin_hw_version(&hw_version, & hw_revision)) { switch (hw_version) { diff --git a/boards/px4/fmu-v2/src/spi.c b/boards/px4/fmu-v2/src/spi.c index ca29b39c32..fc2233f30b 100644 --- a/boards/px4/fmu-v2/src/spi.c +++ b/boards/px4/fmu-v2/src/spi.c @@ -41,6 +41,7 @@ * Included Files ************************************************************************************/ +#include <px4_time.h> #include <px4_config.h> #include <stdint.h> @@ -420,7 +421,7 @@ __EXPORT void board_spi_reset(int ms) stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0); /* wait for the sensor rail to reach GND */ - usleep(ms * 1000); + px4_usleep(ms * 1000); warnx("reset done, %d ms", ms); /* re-enable power */ @@ -429,7 +430,7 @@ __EXPORT void board_spi_reset(int ms) stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1); /* wait a bit before starting SPI, different times didn't influence results */ - usleep(100); + px4_usleep(100); /* reconfigure the SPI pins */ stm32_configgpio(GPIO_SPI1_SCK); diff --git a/platforms/posix/src/main.cpp b/platforms/posix/src/main.cpp index 7cf1cae21a..b504b434fa 100644 --- a/platforms/posix/src/main.cpp +++ b/platforms/posix/src/main.cpp @@ -61,11 +61,11 @@ #include <sys/stat.h> #include <stdlib.h> +#include <px4_time.h> #include <px4_log.h> #include <px4_getopt.h> #include <px4_tasks.h> #include <px4_posix.h> -#include <px4_log.h> #include "apps.h" #include "px4_middleware.h" @@ -544,7 +544,7 @@ int run_startup_script(const std::string &commands_file, const std::string &abso void wait_to_exit() { while (!_exit_requested) { - usleep(100000); + px4_usleep(100000); } } diff --git a/src/drivers/barometer/ms5611/ms5611.cpp b/src/drivers/barometer/ms5611/ms5611.cpp index 3890c859ee..8d03cf947d 100644 --- a/src/drivers/barometer/ms5611/ms5611.cpp +++ b/src/drivers/barometer/ms5611/ms5611.cpp @@ -313,7 +313,7 @@ MS5611::init() break; } - usleep(MS5611_CONVERSION_INTERVAL); + px4_usleep(MS5611_CONVERSION_INTERVAL); if (OK != collect()) { ret = -EIO; @@ -326,7 +326,7 @@ MS5611::init() break; } - usleep(MS5611_CONVERSION_INTERVAL); + px4_usleep(MS5611_CONVERSION_INTERVAL); if (OK != collect()) { ret = -EIO; @@ -429,7 +429,7 @@ MS5611::read(struct file *filp, char *buffer, size_t buflen) break; } - usleep(MS5611_CONVERSION_INTERVAL); + px4_usleep(MS5611_CONVERSION_INTERVAL); if (OK != collect()) { ret = -EIO; @@ -442,7 +442,7 @@ MS5611::read(struct file *filp, char *buffer, size_t buflen) break; } - usleep(MS5611_CONVERSION_INTERVAL); + px4_usleep(MS5611_CONVERSION_INTERVAL); if (OK != collect()) { ret = -EIO; diff --git a/src/drivers/barometer/ms5611/ms5611_i2c.cpp b/src/drivers/barometer/ms5611/ms5611_i2c.cpp index e67d6e10ea..3b21dd9171 100644 --- a/src/drivers/barometer/ms5611/ms5611_i2c.cpp +++ b/src/drivers/barometer/ms5611/ms5611_i2c.cpp @@ -40,6 +40,7 @@ /* XXX trim includes */ #include <px4_config.h> #include <px4_defines.h> +#include <px4_time.h> #include <sys/types.h> #include <stdint.h> @@ -238,7 +239,7 @@ MS5611_I2C::_read_prom() * Wait for PROM contents to be in the device (2.8 ms) in the case we are * called immediately after reset. */ - usleep(3000); + px4_usleep(3000); uint8_t last_val = 0; bool bits_stuck = true; diff --git a/src/drivers/barometer/ms5611/ms5611_spi.cpp b/src/drivers/barometer/ms5611/ms5611_spi.cpp index 2f52f6cf6e..7a8ee8a0fe 100644 --- a/src/drivers/barometer/ms5611/ms5611_spi.cpp +++ b/src/drivers/barometer/ms5611/ms5611_spi.cpp @@ -38,6 +38,7 @@ */ /* XXX trim includes */ +#include <px4_time.h> #include <px4_config.h> #include <sys/types.h> @@ -248,7 +249,7 @@ MS5611_SPI::_read_prom() * Wait for PROM contents to be in the device (2.8 ms) in the case we are * called immediately after reset. */ - usleep(3000); + px4_usleep(3000); /* read and convert PROM words */ bool all_zero = true; diff --git a/src/drivers/batt_smbus/batt_smbus.cpp b/src/drivers/batt_smbus/batt_smbus.cpp index 63e80a4993..0a033453c3 100644 --- a/src/drivers/batt_smbus/batt_smbus.cpp +++ b/src/drivers/batt_smbus/batt_smbus.cpp @@ -269,7 +269,7 @@ void BATT_SMBUS::cycle() } else { while (_should_suspend) { - usleep(200000); + px4_usleep(200000); } // Schedule a fresh cycle call when the measurement is done. @@ -444,7 +444,7 @@ int BATT_SMBUS::get_startup_info() if (lifetime_data_flush() == PX4_OK) { // Flush needs time to complete, otherwise device is busy. 100ms not enough, 200ms works. - usleep(200000); + px4_usleep(200000); if (lifetime_read_block_one() == PX4_OK) { if (_lifetime_max_delta_cell_voltage > BATT_CELL_VOLTAGE_THRESHOLD_FAILED) { @@ -668,11 +668,11 @@ int BATT_SMBUS::custom_command(int argc, char *argv[]) if (PX4_OK != obj->dataflash_write(address, tx_buf, length)) { PX4_INFO("Dataflash write failed: %d", address); - usleep(100000); + px4_usleep(100000); return 1; } else { - usleep(100000); + px4_usleep(100000); return 0; } } diff --git a/src/drivers/differential_pressure/ms5525/MS5525.cpp b/src/drivers/differential_pressure/ms5525/MS5525.cpp index 2c830b7e12..4f8e077209 100644 --- a/src/drivers/differential_pressure/ms5525/MS5525.cpp +++ b/src/drivers/differential_pressure/ms5525/MS5525.cpp @@ -70,7 +70,7 @@ MS5525::init_ms5525() return false; } - usleep(3000); + px4_usleep(3000); // Step 2 - read calibration coefficients from prom diff --git a/src/drivers/differential_pressure/sdp3x/SDP3X.cpp b/src/drivers/differential_pressure/sdp3x/SDP3X.cpp index 0715922c61..cf632b4db3 100644 --- a/src/drivers/differential_pressure/sdp3x/SDP3X.cpp +++ b/src/drivers/differential_pressure/sdp3x/SDP3X.cpp @@ -70,7 +70,7 @@ SDP3X::init_sdp3x() } // wait until sensor is ready - usleep(20000); + px4_usleep(20000); // step 2 - configure ret = write_command(SDP3X_CONT_MEAS_AVG_MODE); @@ -81,7 +81,7 @@ SDP3X::init_sdp3x() return false; } - usleep(10000); + px4_usleep(10000); // step 3 - get scale uint8_t val[9]; diff --git a/src/drivers/distance_sensor/leddar_one/leddar_one.cpp b/src/drivers/distance_sensor/leddar_one/leddar_one.cpp index 784a8b1b9f..c0a9b68eca 100644 --- a/src/drivers/distance_sensor/leddar_one/leddar_one.cpp +++ b/src/drivers/distance_sensor/leddar_one/leddar_one.cpp @@ -357,7 +357,7 @@ int leddar_one::init() return PX4_OK; } - usleep(1000); + px4_usleep(1000); } PX4_ERR("No readings from " NAME); diff --git a/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp b/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp index abf72e5264..31b97dcc7f 100644 --- a/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp +++ b/src/drivers/distance_sensor/ll40ls/LidarLiteI2C.cpp @@ -283,7 +283,7 @@ ssize_t LidarLiteI2C::read(device::file_t *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(LL40LS_CONVERSION_INTERVAL); + px4_usleep(LL40LS_CONVERSION_INTERVAL); /* run the collection phase */ if (OK != collect()) { @@ -353,7 +353,7 @@ int LidarLiteI2C::reset_sensor() } // wait for sensor reset to complete - usleep(50000); + px4_usleep(50000); ret = write_reg(LL40LS_SIG_COUNT_VAL_REG, LL40LS_SIG_COUNT_VAL_MAX); if (ret != OK) { @@ -361,7 +361,7 @@ int LidarLiteI2C::reset_sensor() } // wait for register write to complete - usleep(1000); + px4_usleep(1000); return OK; } @@ -374,7 +374,7 @@ void LidarLiteI2C::print_registers() _pause_measurements = true; printf("ll40ls registers\n"); // wait for a while to ensure the lidar is in a ready state - usleep(50000); + px4_usleep(50000); for (uint8_t reg = 0; reg <= 0x67; reg++) { uint8_t val = 0; diff --git a/src/drivers/distance_sensor/mb12xx/mb12xx.cpp b/src/drivers/distance_sensor/mb12xx/mb12xx.cpp index 67afacf2f4..f1d5ceaef6 100644 --- a/src/drivers/distance_sensor/mb12xx/mb12xx.cpp +++ b/src/drivers/distance_sensor/mb12xx/mb12xx.cpp @@ -264,7 +264,7 @@ MB12XX::init() } // XXX we should find out why we need to wait 200 ms here - usleep(200000); + px4_usleep(200000); /* check for connected rangefinders on each i2c port: We start from i2c base address (0x70 = 112) and count downwards @@ -440,7 +440,7 @@ MB12XX::read(device::file_t *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(_cycling_rate * 2); + px4_usleep(_cycling_rate * 2); /* run the collection phase */ if (OK != collect()) { diff --git a/src/drivers/distance_sensor/pga460/pga460.cpp b/src/drivers/distance_sensor/pga460/pga460.cpp index e263b49ee5..648ec8bde6 100644 --- a/src/drivers/distance_sensor/pga460/pga460.cpp +++ b/src/drivers/distance_sensor/pga460/pga460.cpp @@ -113,13 +113,13 @@ int PGA460::initialize_device_settings() return PX4_ERROR; } - usleep(10000); + px4_usleep(10000); // Read to see if eeprom saved data matches desired data, otherwise overwrite eeprom. if (read_eeprom() != PX4_OK) { write_eeprom(); // Allow sufficient time for the device to complete writing to registers. - usleep(10000); + px4_usleep(10000); } // Verify the device is alive. @@ -152,7 +152,7 @@ int PGA460::initialize_thresholds() } // Must wait >50us per datasheet. - usleep(100); + px4_usleep(100); if (read_threshold_registers() == PX4_OK) { return PX4_OK; @@ -183,7 +183,7 @@ uint32_t PGA460::collect_results() bytes_available -= ret; - usleep(1000); + px4_usleep(1000); } while (bytes_available > 0); @@ -250,7 +250,7 @@ float PGA460::get_temperature() } // The pga460 requires a 2ms delay per the datasheet. - usleep(5000); + px4_usleep(5000); buf_tx[1] = TNLR; ret = ::write(_fd, &buf_tx[0], sizeof(buf_tx) - 2); @@ -259,7 +259,7 @@ float PGA460::get_temperature() return PX4_ERROR; } - usleep(10000); + px4_usleep(10000); uint8_t buf_rx[4] = {}; int bytes_available = sizeof(buf_rx); @@ -278,7 +278,7 @@ float PGA460::get_temperature() bytes_available -= ret; - usleep(1000); + px4_usleep(1000); } while (bytes_available > 0); @@ -528,7 +528,7 @@ int PGA460::read_eeprom() return PX4_ERROR; } - usleep(10000); + px4_usleep(10000); int bytes_available = sizeof(buf_rx); int total_bytes = 0; @@ -546,7 +546,7 @@ int PGA460::read_eeprom() bytes_available -= ret; - usleep(1000); + px4_usleep(1000); } while (bytes_available > 0); @@ -580,7 +580,7 @@ uint8_t PGA460::read_register(const uint8_t reg) return PX4_ERROR; } - usleep(10000); + px4_usleep(10000); uint8_t buf_rx[3] = {}; int bytes_available = sizeof(buf_rx); @@ -599,7 +599,7 @@ uint8_t PGA460::read_register(const uint8_t reg) bytes_available -= ret; - usleep(1000); + px4_usleep(1000); } while (bytes_available > 0); @@ -628,7 +628,7 @@ int PGA460::read_threshold_registers() return PX4_ERROR; } - usleep(10000); + px4_usleep(10000); uint8_t buf_rx[array_size + 2] = {}; int bytes_available = sizeof(buf_rx); @@ -647,7 +647,7 @@ int PGA460::read_threshold_registers() bytes_available -= ret; - usleep(1000); + px4_usleep(1000); } while (bytes_available > 0); @@ -669,7 +669,7 @@ int PGA460::request_results() { uint8_t buf_tx[2] = {SYNCBYTE, UMR}; int ret = ::write(_fd, &buf_tx[0], sizeof(buf_tx)); - usleep(10000); + px4_usleep(10000); if(!ret) { return PX4_ERROR; @@ -707,7 +707,7 @@ void PGA460::run() // Control rate. uint64_t loop_time = hrt_absolute_time() - _start_loop; uint32_t sleep_time = (loop_time > POLL_RATE_US) ? 0 : POLL_RATE_US - loop_time; - usleep(sleep_time); + px4_usleep(sleep_time); _start_loop = hrt_absolute_time(); request_results(); @@ -856,17 +856,17 @@ int PGA460::write_eeprom() } // Needs time, see datasheet timing requirements. - usleep(5000); + px4_usleep(5000); unlock_eeprom(); flash_eeprom(); - usleep(5000); + px4_usleep(5000); uint8_t result = 0; // Give up to 100ms for ee_cntrl register to reflect a successful eeprom write. for (int i = 0; i < 100; i++) { result = read_register(EE_CNTRL_ADDR); - usleep(5000); + px4_usleep(5000); if (result & 1 << 2) { PX4_INFO("EEPROM write successful"); diff --git a/src/drivers/distance_sensor/sf0x/sf0x.cpp b/src/drivers/distance_sensor/sf0x/sf0x.cpp index a0b40b721a..4614bb2e48 100644 --- a/src/drivers/distance_sensor/sf0x/sf0x.cpp +++ b/src/drivers/distance_sensor/sf0x/sf0x.cpp @@ -420,7 +420,7 @@ SF0X::read(device::file_t *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(_conversion_interval); + px4_usleep(_conversion_interval); /* run the collection phase */ if (OK != collect()) { diff --git a/src/drivers/distance_sensor/sf1xx/sf1xx.cpp b/src/drivers/distance_sensor/sf1xx/sf1xx.cpp index e5a0a6c78b..de9791e12e 100644 --- a/src/drivers/distance_sensor/sf1xx/sf1xx.cpp +++ b/src/drivers/distance_sensor/sf1xx/sf1xx.cpp @@ -439,7 +439,7 @@ SF1XX::read(device::file_t *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(_conversion_interval); + px4_usleep(_conversion_interval); /* run the collection phase */ if (OK != collect()) { diff --git a/src/drivers/distance_sensor/srf02/srf02.cpp b/src/drivers/distance_sensor/srf02/srf02.cpp index d128470871..4a64e43d56 100644 --- a/src/drivers/distance_sensor/srf02/srf02.cpp +++ b/src/drivers/distance_sensor/srf02/srf02.cpp @@ -264,7 +264,7 @@ SRF02::init() } // XXX we should find out why we need to wait 200 ms here - usleep(200000); + px4_usleep(200000); /* check for connected rangefinders on each i2c port: We start from i2c base address (0x70 = 112) and count downwards @@ -440,7 +440,7 @@ SRF02::read(device::file_t *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(_cycling_rate * 2); + px4_usleep(_cycling_rate * 2); /* run the collection phase */ if (OK != collect()) { diff --git a/src/drivers/distance_sensor/teraranger/teraranger.cpp b/src/drivers/distance_sensor/teraranger/teraranger.cpp index 6cd5f59354..75a27d0ccc 100644 --- a/src/drivers/distance_sensor/teraranger/teraranger.cpp +++ b/src/drivers/distance_sensor/teraranger/teraranger.cpp @@ -517,7 +517,7 @@ TERARANGER::read(device::file_t *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(TERARANGER_CONVERSION_INTERVAL); + px4_usleep(TERARANGER_CONVERSION_INTERVAL); /* run the collection phase */ if (OK != collect()) { diff --git a/src/drivers/distance_sensor/tfmini/tfmini.cpp b/src/drivers/distance_sensor/tfmini/tfmini.cpp index 6c9f2da4cd..c3222d01e2 100644 --- a/src/drivers/distance_sensor/tfmini/tfmini.cpp +++ b/src/drivers/distance_sensor/tfmini/tfmini.cpp @@ -451,7 +451,7 @@ TFMINI::read(device::file_t *filp, char *buffer, size_t buflen) _reports->flush(); /* wait for it to complete */ - usleep(_conversion_interval); + px4_usleep(_conversion_interval); /* run the collection phase */ if (OK != collect()) { diff --git a/src/drivers/distance_sensor/ulanding/ulanding.cpp b/src/drivers/distance_sensor/ulanding/ulanding.cpp index bbf6fdc5d3..5f58560bcd 100644 --- a/src/drivers/distance_sensor/ulanding/ulanding.cpp +++ b/src/drivers/distance_sensor/ulanding/ulanding.cpp @@ -169,7 +169,7 @@ Radar::~Radar() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { @@ -436,7 +436,7 @@ Radar::task_main() if (pret < 0) { PX4_DEBUG("radar serial port poll error"); // sleep a bit before next try - usleep(100000); + px4_usleep(100000); continue; } diff --git a/src/drivers/gps/devices b/src/drivers/gps/devices index 3d7df42aee..2fecb4912d 160000 --- a/src/drivers/gps/devices +++ b/src/drivers/gps/devices @@ -1 +1 @@ -Subproject commit 3d7df42aee85f14d3100cf87a819dfb557e71e20 +Subproject commit 2fecb4912dd8c97a9eee42c5dbecfb58c4aeb9ee diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index e372a0b884..8a6d566831 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -300,7 +300,7 @@ GPS::~GPS() unsigned int i = 0; do { - usleep(20000); // 20 ms + px4_usleep(20000); // 20 ms ++i; } while (_secondary_instance && i < 100); } @@ -400,11 +400,11 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout) err = ioctl(_serial_fd, FIONREAD, (unsigned long)&bytes_available); if (err != 0 || bytes_available < (int)character_count) { - usleep(sleeptime); + px4_usleep(sleeptime); } #else - usleep(sleeptime); + px4_usleep(sleeptime); #endif ret = ::read(_serial_fd, buf, buf_length); @@ -419,7 +419,7 @@ int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout) #else /* For QURT, just use read for now, since this doesn't block, we need to slow it down * just a bit. */ - usleep(10000); + px4_usleep(10000); return ::read(_serial_fd, buf, buf_length); #endif } @@ -693,7 +693,7 @@ GPS::run() publish(); - usleep(200000); + px4_usleep(200000); } else { @@ -810,7 +810,7 @@ GPS::run() case GPS_DRIVER_MODE_ASHTECH: _mode = GPS_DRIVER_MODE_UBX; - usleep(500000); // tried all possible drivers. Wait a bit before next round + px4_usleep(500000); // tried all possible drivers. Wait a bit before next round break; default: @@ -818,7 +818,7 @@ GPS::run() } } else { - usleep(500000); + px4_usleep(500000); } } @@ -1139,7 +1139,7 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance) do { /* wait up to 1s */ - usleep(2500); + px4_usleep(2500); } while (!_secondary_instance && ++i < 400); diff --git a/src/drivers/imu/mpu6000/mpu6000.cpp b/src/drivers/imu/mpu6000/mpu6000.cpp index 3c1eda6246..a226c2580d 100644 --- a/src/drivers/imu/mpu6000/mpu6000.cpp +++ b/src/drivers/imu/mpu6000/mpu6000.cpp @@ -56,6 +56,7 @@ */ #include <px4_config.h> +#include <px4_time.h> #include <ecl/geo/geo.h> #include <sys/types.h> @@ -762,7 +763,7 @@ int MPU6000::reset() } perf_count(_reset_retries); - usleep(2000); + px4_usleep(2000); } // Hold off sampling for 30 ms @@ -775,11 +776,11 @@ int MPU6000::reset() return -EIO; } - usleep(1000); + px4_usleep(1000); // SAMPLE RATE _set_sample_rate(_sample_rate); - usleep(1000); + px4_usleep(1000); _set_dlpf_filter(MPU6000_DEFAULT_ONCHIP_FILTER_FREQ); @@ -787,10 +788,10 @@ int MPU6000::reset() _set_icm_acc_dlpf_filter(MPU6000_DEFAULT_ONCHIP_FILTER_FREQ); } - usleep(1000); + px4_usleep(1000); // Gyro scale 2000 deg/s () write_checked_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS); - usleep(1000); + px4_usleep(1000); // correct gyro scale factors // scale to rad/s in SI units @@ -802,13 +803,13 @@ int MPU6000::reset() set_accel_range(MPU6000_ACCEL_DEFAULT_RANGE_G); - usleep(1000); + px4_usleep(1000); // INT CFG => Interrupt on Data Ready write_checked_reg(MPUREG_INT_ENABLE, BIT_RAW_RDY_EN); // INT: Raw data ready - usleep(1000); + px4_usleep(1000); write_checked_reg(MPUREG_INT_PIN_CFG, BIT_INT_ANYRD_2CLEAR); // INT: Clear on any read - usleep(1000); + px4_usleep(1000); if (is_icm_device()) { write_checked_reg(MPUREG_ICM_UNDOC1, MPUREG_ICM_UNDOC1_VALUE); @@ -816,7 +817,7 @@ int MPU6000::reset() // Oscillator set // write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ); - usleep(1000); + px4_usleep(1000); return OK; } diff --git a/src/drivers/imu/mpu9250/mag.cpp b/src/drivers/imu/mpu9250/mag.cpp index cdbc35f3da..402bc69a68 100644 --- a/src/drivers/imu/mpu9250/mag.cpp +++ b/src/drivers/imu/mpu9250/mag.cpp @@ -42,6 +42,7 @@ #include <px4_config.h> #include <px4_log.h> +#include <px4_time.h> #include <lib/perf/perf_counter.h> #include <drivers/drv_hrt.h> #include <drivers/device/spi.h> @@ -353,7 +354,7 @@ void MPU9250_mag::passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) { set_passthrough(reg, size); - usleep(25 + 25 * size); // wait for the value to be read from slave + px4_usleep(25 + 25 * size); // wait for the value to be read from slave read_block(AK_MPU_OR_ICM(MPUREG_EXT_SENS_DATA_00, ICMREG_20948_EXT_SLV_SENS_DATA_00), buf, size); _parent->write_reg(AK_MPU_OR_ICM(MPUREG_I2C_SLV0_CTRL, ICMREG_20948_I2C_SLV0_CTRL), 0); // disable new reads } @@ -388,7 +389,7 @@ void MPU9250_mag::passthrough_write(uint8_t reg, uint8_t val) { set_passthrough(reg, 1, &val); - usleep(50); // wait for the value to be written to slave + px4_usleep(50); // wait for the value to be written to slave _parent->write_reg(AK_MPU_OR_ICM(MPUREG_I2C_SLV0_CTRL, ICMREG_20948_I2C_SLV0_CTRL), 0); // disable new writes } @@ -428,7 +429,7 @@ MPU9250_mag::ak8963_read_adjustments(void) float ak8963_ASA[3]; write_reg(AK8963REG_CNTL1, AK8963_FUZE_MODE | AK8963_16BIT_ADC); - usleep(50); + px4_usleep(50); if (_interface != nullptr) { _interface->read(AK8963REG_ASAX, response, 3); diff --git a/src/drivers/imu/mpu9250/mpu9250.cpp b/src/drivers/imu/mpu9250/mpu9250.cpp index 1c5792371e..4127f10977 100644 --- a/src/drivers/imu/mpu9250/mpu9250.cpp +++ b/src/drivers/imu/mpu9250/mpu9250.cpp @@ -42,6 +42,7 @@ */ #include <px4_config.h> +#include <px4_time.h> #include <lib/ecl/geo/geo.h> #include <lib/perf/perf_counter.h> #include <systemlib/conversions.h> @@ -436,7 +437,7 @@ int MPU9250::reset() * */ - usleep(110000); + px4_usleep(110000); // Hold off sampling until done (100 MS will be shortened) state = px4_enter_critical_section(); diff --git a/src/drivers/lights/rgbled/rgbled.cpp b/src/drivers/lights/rgbled/rgbled.cpp index f72cf2e7da..1f5f873457 100644 --- a/src/drivers/lights/rgbled/rgbled.cpp +++ b/src/drivers/lights/rgbled/rgbled.cpp @@ -152,7 +152,7 @@ RGBLED::~RGBLED() int counter = 0; while (_running && ++counter < 10) { - usleep(100000); + px4_usleep(100000); } } diff --git a/src/drivers/magnetometer/hmc5883/hmc5883.cpp b/src/drivers/magnetometer/hmc5883/hmc5883.cpp index 3b6e5131b5..b5738926ad 100644 --- a/src/drivers/magnetometer/hmc5883/hmc5883.cpp +++ b/src/drivers/magnetometer/hmc5883/hmc5883.cpp @@ -39,6 +39,7 @@ #include <px4_config.h> #include <px4_defines.h> +#include <px4_time.h> #include <drivers/device/i2c.h> @@ -591,7 +592,7 @@ HMC5883::read(struct file *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(HMC5883_CONVERSION_INTERVAL); + px4_usleep(HMC5883_CONVERSION_INTERVAL); /* run the collection phase */ if (OK != collect()) { diff --git a/src/drivers/magnetometer/lis3mdl/lis3mdl.cpp b/src/drivers/magnetometer/lis3mdl/lis3mdl.cpp index 6935ddfe21..262c812780 100644 --- a/src/drivers/magnetometer/lis3mdl/lis3mdl.cpp +++ b/src/drivers/magnetometer/lis3mdl/lis3mdl.cpp @@ -39,6 +39,7 @@ * Based on the hmc5883 driver. */ +#include <px4_time.h> #include "lis3mdl.h" LIS3MDL::LIS3MDL(device::Device *interface, const char *path, enum Rotation rotation) : @@ -146,7 +147,7 @@ LIS3MDL::calibrate(struct file *file_pointer, unsigned enable) goto out; } - usleep(20000); + px4_usleep(20000); /* discard 10 samples to let the sensor settle */ for (uint8_t i = 0; i < num_samples; i++) { @@ -211,7 +212,7 @@ LIS3MDL::calibrate(struct file *file_pointer, unsigned enable) goto out; } - usleep(60000); + px4_usleep(60000); /* discard 10 samples to let the sensor settle */ for (uint8_t i = 0; i < num_samples; i++) { @@ -285,7 +286,7 @@ out: set_range(4); set_default_register_values(); - usleep(20000); + px4_usleep(20000); return ret; } @@ -687,7 +688,7 @@ LIS3MDL::read(struct file *file_pointer, char *buffer, size_t buffer_len) } /* wait for it to complete */ - usleep(LIS3MDL_CONVERSION_INTERVAL); + px4_usleep(LIS3MDL_CONVERSION_INTERVAL); /* run the collection phase */ if (collect() != OK) { diff --git a/src/drivers/pwm_input/pwm_input.cpp b/src/drivers/pwm_input/pwm_input.cpp index 1fd655a4ca..5efca66d64 100644 --- a/src/drivers/pwm_input/pwm_input.cpp +++ b/src/drivers/pwm_input/pwm_input.cpp @@ -42,6 +42,7 @@ */ #include <px4_config.h> +#include <px4_time.h> #include <nuttx/arch.h> #include <nuttx/irq.h> @@ -587,7 +588,7 @@ static void pwmin_test(void) } else { /* no data, retry in 2 ms */ - ::usleep(2000); + px4_usleep(2000); } } diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp index 2df9c71368..e2a345a1ce 100644 --- a/src/drivers/px4flow/px4flow.cpp +++ b/src/drivers/px4flow/px4flow.cpp @@ -800,7 +800,7 @@ start(int argc, char *argv[]) if (retry_nr < START_RETRY_COUNT) { /* lets not be too verbose */ // PX4_WARN("PX4FLOW not found on I2C busses. Retrying in %d ms. Giving up in %d retries.", START_RETRY_TIMEOUT, START_RETRY_COUNT - retry_nr); - usleep(START_RETRY_TIMEOUT * 1000); + px4_usleep(START_RETRY_TIMEOUT * 1000); retry_nr++; } else { diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 334f9d82a8..814b6e9d92 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -513,7 +513,7 @@ PX4IO::~PX4IO() /* spin waiting for the task to stop */ for (unsigned i = 0; (i < 10) && (_task != -1); i++) { /* give it another 100ms */ - usleep(100000); + px4_usleep(100000); } /* well, kill it anyway, though this will probably crash */ @@ -606,7 +606,7 @@ PX4IO::init() hrt_abstime start_try_time = hrt_absolute_time(); do { - usleep(2000); + px4_usleep(2000); protocol = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION); } while (protocol == _io_reg_get_error && (hrt_elapsed_time(&start_try_time) < 700U * 1000U)); @@ -709,7 +709,7 @@ PX4IO::init() } /* wait 10 ms */ - usleep(10000); + px4_usleep(10000); /* abort after 5s */ if ((hrt_absolute_time() - try_start_time) / 1000 > 3000) { @@ -757,7 +757,7 @@ PX4IO::init() } /* wait 50 ms */ - usleep(50000); + px4_usleep(50000); /* abort after 5s */ if ((hrt_absolute_time() - try_start_time) / 1000 > 2000) { @@ -2022,7 +2022,7 @@ PX4IO::print_debug() fds[0].fd = io_fd; fds[0].events = POLLIN; - usleep(500); + px4_usleep(500); int pret = ::poll(fds, sizeof(fds) / sizeof(fds[0]), 0); if (pret > 0) { @@ -2103,7 +2103,7 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries) ret = io_reg_set(PX4IO_PAGE_MIXERLOAD, 0, (uint16_t *)frame, total_len / 2); if (ret) { - usleep(333); + px4_usleep(333); } else { break; @@ -2139,7 +2139,7 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries) ret = io_reg_set(PX4IO_PAGE_MIXERLOAD, 0, (uint16_t *)frame, (sizeof(px4io_mixdata) + 2) / 2); if (ret) { - usleep(333); + px4_usleep(333); } else { break; @@ -2665,12 +2665,12 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) arg == DSMX_BIND_PULSES || arg == DSMX8_BIND_PULSES) { io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); - usleep(500000); + px4_usleep(500000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); - usleep(72000); + px4_usleep(72000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); - usleep(50000); + px4_usleep(50000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); ret = OK; @@ -3190,7 +3190,7 @@ test(void) } } - usleep(250); + px4_usleep(250); /* readback servo values */ for (unsigned i = 0; i < servo_count; i++) { @@ -3316,7 +3316,7 @@ lockdown(int argc, char *argv[]) } } - usleep(10000); + px4_usleep(10000); } if (hrt_elapsed_time(&start) > timeout) { diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index b0af24aa08..84c3ddaeb8 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -37,6 +37,7 @@ */ #include <px4_config.h> +#include <px4_time.h> #include <sys/types.h> #include <stdlib.h> @@ -127,7 +128,7 @@ PX4IO_Uploader::upload(const char *filenames[]) break; } else { - usleep(10000); + px4_usleep(10000); } } diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp index 706ae0c52d..8b5835d3b7 100644 --- a/src/drivers/stm32/adc/adc.cpp +++ b/src/drivers/stm32/adc/adc.cpp @@ -220,7 +220,7 @@ int board_adc_init() /* do calibration if supported */ #ifdef ADC_CR2_CAL rCR2 |= ADC_CR2_CAL; - usleep(100); + px4_usleep(100); if (rCR2 & ADC_CR2_CAL) { return -1; @@ -260,11 +260,11 @@ int board_adc_init() /* power-cycle the ADC and turn it on */ rCR2 &= ~ADC_CR2_ADON; - usleep(10); + px4_usleep(10); rCR2 |= ADC_CR2_ADON; - usleep(10); + px4_usleep(10); rCR2 |= ADC_CR2_ADON; - usleep(10); + px4_usleep(10); /* kick off a sample and wait for it to complete */ hrt_abstime now = hrt_absolute_time(); @@ -541,7 +541,7 @@ test(void) } printf("\n"); - usleep(500000); + px4_usleep(500000); } exit(0); diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index 871f70cf5c..af9dddf0f9 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -331,7 +331,7 @@ ToneAlarm::~ToneAlarm() int counter = 0; while (_running && ++counter < 10) { - usleep(100000); + px4_usleep(100000); } } diff --git a/src/drivers/tone_alarm_sim/tone_alarm.cpp b/src/drivers/tone_alarm_sim/tone_alarm.cpp index 05c5877ff9..c5dc913b11 100644 --- a/src/drivers/tone_alarm_sim/tone_alarm.cpp +++ b/src/drivers/tone_alarm_sim/tone_alarm.cpp @@ -135,7 +135,7 @@ ToneAlarm::~ToneAlarm() int counter = 0; while (_running && ++counter < 10) { - usleep(100000); + px4_usleep(100000); } } diff --git a/src/examples/bottle_drop/bottle_drop.cpp b/src/examples/bottle_drop/bottle_drop.cpp index 165eb5ae6a..eca17abc9c 100644 --- a/src/examples/bottle_drop/bottle_drop.cpp +++ b/src/examples/bottle_drop/bottle_drop.cpp @@ -206,7 +206,7 @@ BottleDrop::~BottleDrop() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { @@ -261,7 +261,7 @@ BottleDrop::open_bay() actuators_publish(); - usleep(500 * 1000); + px4_usleep(500 * 1000); } void @@ -276,7 +276,7 @@ BottleDrop::close_bay() actuators_publish(); // delay until the bay is closed - usleep(500 * 1000); + px4_usleep(500 * 1000); } void @@ -292,7 +292,7 @@ BottleDrop::drop() } while (hrt_elapsed_time(&_doors_opened) < 500 * 1000 && hrt_elapsed_time(&starttime) < 2000000) { - usleep(50000); + px4_usleep(50000); warnx("delayed by door!"); } @@ -304,7 +304,7 @@ BottleDrop::drop() warnx("dropping now"); // Give it time to drop - usleep(1000 * 1000); + px4_usleep(1000 * 1000); } void @@ -728,7 +728,7 @@ BottleDrop::task_main() // update_actuators(); // run at roughly 100 Hz - usleep(sleeptime_us); + px4_usleep(sleeptime_us); dt_runs = hrt_elapsed_time(&last_run) / 1e6f; last_run = hrt_absolute_time(); diff --git a/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp b/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp index 273d780469..d2e0580fec 100644 --- a/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp +++ b/src/examples/px4_mavlink_debug/px4_mavlink_debug.cpp @@ -118,7 +118,7 @@ int px4_mavlink_debug_main(int argc, char *argv[]) warnx("sent one more value.."); value_counter++; - usleep(500000); + px4_usleep(500000); } return 0; diff --git a/src/include/visibility.h b/src/include/visibility.h index 9f1cf06c6f..ff2c0db93f 100644 --- a/src/include/visibility.h +++ b/src/include/visibility.h @@ -66,6 +66,11 @@ #define system_exit exit #ifdef __PX4_POSIX #include <stdlib.h> + +#include <unistd.h> +#define system_usleep usleep +#pragma GCC poison usleep + #ifdef __cplusplus #include <cstdlib> #endif @@ -80,5 +85,11 @@ #ifdef __cplusplus #include <cstdlib> #endif + +// We don't poison usleep and sleep on NuttX because it is used in dependencies +// like uavcan and we don't need to fake time on the real system. +#include <unistd.h> +#define system_usleep usleep + #pragma GCC poison getenv setenv putenv #endif /* __PX4_NUTTX */ diff --git a/src/lib/cdev/posix/cdev_platform.cpp b/src/lib/cdev/posix/cdev_platform.cpp index a892e17da2..8418f6c4ca 100644 --- a/src/lib/cdev/posix/cdev_platform.cpp +++ b/src/lib/cdev/posix/cdev_platform.cpp @@ -340,7 +340,7 @@ extern "C" { #endif while (sim_delay) { - usleep(100); + px4_usleep(100); } PX4_DEBUG("Called px4_poll timeout = %d", timeout); diff --git a/src/lib/cdev/test/cdevtest_example.cpp b/src/lib/cdev/test/cdevtest_example.cpp index abf66acfb1..7b8374ee1f 100644 --- a/src/lib/cdev/test/cdevtest_example.cpp +++ b/src/lib/cdev/test/cdevtest_example.cpp @@ -234,7 +234,7 @@ int CDevExample::do_poll(int fd, int timeout, int iterations, int delayms_after_ } if (delayms_after_poll) { - usleep(delayms_after_poll * 1000); + px4_usleep(delayms_after_poll * 1000); } loop_count++; diff --git a/src/lib/parameters/parameters.cpp b/src/lib/parameters/parameters.cpp index c587a8751a..879be08fd6 100644 --- a/src/lib/parameters/parameters.cpp +++ b/src/lib/parameters/parameters.cpp @@ -1280,7 +1280,7 @@ param_import_internal(int fd, bool mark_saved) do { result = bson_decoder_next(&decoder); - usleep(1); + px4_usleep(1); } while (result > 0); diff --git a/src/lib/rc/dsm.cpp b/src/lib/rc/dsm.cpp index 6821e69ebd..765bbdaaef 100644 --- a/src/lib/rc/dsm.cpp +++ b/src/lib/rc/dsm.cpp @@ -57,7 +57,7 @@ #include <nuttx/arch.h> #define dsm_udelay(arg) up_udelay(arg) #else -#define dsm_udelay(arg) usleep(arg) +#define dsm_udelay(arg) px4_usleep(arg) #endif // #define DSM_DEBUG diff --git a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp index f72f11e694..187f6d54ee 100644 --- a/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp +++ b/src/modules/attitude_estimator_q/attitude_estimator_q_main.cpp @@ -214,7 +214,7 @@ AttitudeEstimatorQ::~AttitudeEstimatorQ() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { @@ -282,7 +282,7 @@ void AttitudeEstimatorQ::task_main() if (ret < 0) { // Poll error, sleep and try again - usleep(10000); + px4_usleep(10000); PX4_WARN("POLL ERROR"); continue; diff --git a/src/modules/camera_feedback/camera_feedback.cpp b/src/modules/camera_feedback/camera_feedback.cpp index 206cf85084..6738acad05 100644 --- a/src/modules/camera_feedback/camera_feedback.cpp +++ b/src/modules/camera_feedback/camera_feedback.cpp @@ -76,7 +76,7 @@ CameraFeedback::~CameraFeedback() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 590a6f52b3..9716a8678b 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -310,7 +310,7 @@ int commander_main(int argc, char *argv[]) unsigned i; for (i = 0; i < max_wait_steps; i++) { - usleep(max_wait_us / max_wait_steps); + px4_usleep(max_wait_us / max_wait_steps); if (thread_running) { break; @@ -1629,7 +1629,7 @@ Commander::run() * so lets reset to a classic non-usb state. */ mavlink_log_critical(&mavlink_log_pub, "USB disconnected, rebooting.") - usleep(400000); + px4_usleep(400000); px4_shutdown_request(true, false); } } @@ -2101,7 +2101,7 @@ Commander::run() &mavlink_log_pub, &status_flags, arm_requirements, hrt_elapsed_time(&commander_boot_timestamp)); if (arming_ret != TRANSITION_CHANGED) { - usleep(100000); + px4_usleep(100000); print_reject_arm("NOT ARMING: Preflight checks failed"); } } @@ -2556,7 +2556,7 @@ Commander::run() arm_auth_update(now, params_updated || param_init_forced); - usleep(COMMANDER_MONITORING_INTERVAL); + px4_usleep(COMMANDER_MONITORING_INTERVAL); } thread_should_exit = true; @@ -3574,19 +3574,19 @@ void *commander_low_prio_loop(void *arg) if (((int)(cmd.param1)) == 1) { answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub); - usleep(100000); + px4_usleep(100000); /* reboot */ px4_shutdown_request(true, false); } else if (((int)(cmd.param1)) == 2) { answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub); - usleep(100000); + px4_usleep(100000); /* shutdown */ px4_shutdown_request(false, false); } else if (((int)(cmd.param1)) == 3) { answer_command(cmd, vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED, command_ack_pub); - usleep(100000); + px4_usleep(100000); /* reboot to bootloader */ px4_shutdown_request(true, true); @@ -3733,7 +3733,7 @@ void *commander_low_prio_loop(void *arg) #ifdef __PX4_QURT // TODO FIXME: on snapdragon the save happens too early when the params // are not set yet. We therefore need to wait some time first. - usleep(1000000); + px4_usleep(1000000); #endif int ret = param_save_default(); @@ -4115,7 +4115,7 @@ void Commander::battery_status_check() if (battery.warning == battery_status_s::BATTERY_WARNING_EMERGENCY) { mavlink_log_critical(&mavlink_log_pub, "DANGEROUSLY LOW BATTERY, SHUT SYSTEM DOWN"); - usleep(200000); + px4_usleep(200000); int ret_val = px4_shutdown_request(false, false); @@ -4123,7 +4123,7 @@ void Commander::battery_status_check() mavlink_log_critical(&mavlink_log_pub, "SYSTEM DOES NOT SUPPORT SHUTDOWN"); } else { - while (1) { usleep(1); } + while (1) { px4_usleep(1); } } } } diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index 040948b1bb..29302ed7d8 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -441,7 +441,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub) if (res == PX4_OK) { /* if there is a any preflight-check system response, let the barrage of messages through */ - usleep(200000); + px4_usleep(200000); calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name); @@ -450,7 +450,7 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub) } /* give this message enough time to propagate */ - usleep(600000); + px4_usleep(600000); return res; } diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 52815cb44c..8929921b08 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -121,7 +121,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub) } calibration_log_critical(mavlink_log_pub, "[cal] Ensure sensor is not measuring wind"); - usleep(500 * 1000); + px4_usleep(500 * 1000); while (calibration_counter < calibration_count) { @@ -198,7 +198,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub) calibration_log_info(mavlink_log_pub, "[cal] Offset of %d Pascal", (int)diff_pres_offset); /* wait 500 ms to ensure parameter propagated through the system */ - usleep(500 * 1000); + px4_usleep(500 * 1000); calibration_log_critical(mavlink_log_pub, "[cal] Blow across front of pitot without touching"); @@ -277,7 +277,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub) /* Wait 2sec for the airflow to stop and ensure the driver filter has caught up, otherwise * the followup preflight checks might fail. */ - usleep(2e6); + px4_usleep(2e6); normal_return: calibrate_cancel_unsubscribe(cancel_sub); diff --git a/src/modules/commander/arm_auth.cpp b/src/modules/commander/arm_auth.cpp index ed25652375..891f9c7038 100644 --- a/src/modules/commander/arm_auth.cpp +++ b/src/modules/commander/arm_auth.cpp @@ -120,7 +120,7 @@ static uint8_t _auth_method_arm_req_check() } /* 0.5ms */ - usleep(500); + px4_usleep(500); now = hrt_absolute_time(); } diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp index 4ca23444af..4ff9a36c19 100644 --- a/src/modules/commander/calibration_routines.cpp +++ b/src/modules/commander/calibration_routines.cpp @@ -605,7 +605,7 @@ enum detect_orientation_return detect_orientation(orb_advert_t *mavlink_log_pub, /* not still, reset still start time */ if (t_still != 0) { calibration_log_info(mavlink_log_pub, "[cal] detected motion, hold still..."); - usleep(200000); + px4_usleep(200000); t_still = 0; } } @@ -739,16 +739,16 @@ calibrate_return calibrate_from_orientation(orb_advert_t *mavlink_log_pub, } calibration_log_info(mavlink_log_pub, "[cal] pending:%s", pendingStr); - usleep(20000); + px4_usleep(20000); calibration_log_info(mavlink_log_pub, "[cal] hold vehicle still on a pending side"); - usleep(20000); + px4_usleep(20000); enum detect_orientation_return orient = detect_orientation(mavlink_log_pub, cancel_sub, sub_accel, lenient_still_position); if (orient == DETECT_ORIENTATION_ERROR) { orientation_failures++; calibration_log_info(mavlink_log_pub, "[cal] detected motion, hold still..."); - usleep(20000); + px4_usleep(20000); continue; } @@ -757,14 +757,14 @@ calibrate_return calibrate_from_orientation(orb_advert_t *mavlink_log_pub, orientation_failures++; set_tune(TONE_NOTIFY_NEGATIVE_TUNE); calibration_log_info(mavlink_log_pub, "[cal] %s side already completed", detect_orientation_str(orient)); - usleep(20000); + px4_usleep(20000); continue; } calibration_log_info(mavlink_log_pub, CAL_QGC_ORIENTATION_DETECTED_MSG, detect_orientation_str(orient)); - usleep(20000); + px4_usleep(20000); calibration_log_info(mavlink_log_pub, CAL_QGC_ORIENTATION_DETECTED_MSG, detect_orientation_str(orient)); - usleep(20000); + px4_usleep(20000); orientation_failures = 0; // Call worker routine @@ -775,9 +775,9 @@ calibrate_return calibrate_from_orientation(orb_advert_t *mavlink_log_pub, } calibration_log_info(mavlink_log_pub, CAL_QGC_SIDE_DONE_MSG, detect_orientation_str(orient)); - usleep(20000); + px4_usleep(20000); calibration_log_info(mavlink_log_pub, CAL_QGC_SIDE_DONE_MSG, detect_orientation_str(orient)); - usleep(20000); + px4_usleep(20000); // Note that this side is complete side_data_collected[orient] = true; @@ -787,7 +787,7 @@ calibrate_return calibrate_from_orientation(orb_advert_t *mavlink_log_pub, // temporary priority boost for the white blinking led to come trough rgbled_set_color_and_mode(led_control_s::COLOR_WHITE, led_control_s::MODE_BLINK_FAST, 3, 1); - usleep(200000); + px4_usleep(200000); } if (sub_accel >= 0) { diff --git a/src/modules/commander/calibration_routines.h b/src/modules/commander/calibration_routines.h index a9d6243d04..d644d225d3 100644 --- a/src/modules/commander/calibration_routines.h +++ b/src/modules/commander/calibration_routines.h @@ -140,17 +140,17 @@ bool calibrate_cancel_check(orb_advert_t *mavlink_log_pub, ///< uORB handle to w #define calibration_log_info(_pub, _text, ...) \ do { \ mavlink_and_console_log_info(_pub, _text, ##__VA_ARGS__); \ - usleep(10000); \ + px4_usleep(10000); \ } while(0); #define calibration_log_critical(_pub, _text, ...) \ do { \ mavlink_log_critical(_pub, _text, ##__VA_ARGS__); \ - usleep(10000); \ + px4_usleep(10000); \ } while(0); #define calibration_log_emergency(_pub, _text, ...) \ do { \ mavlink_log_emergency(_pub, _text, ##__VA_ARGS__); \ - usleep(10000); \ + px4_usleep(10000); \ } while(0); diff --git a/src/modules/commander/esc_calibration.cpp b/src/modules/commander/esc_calibration.cpp index 634505dd6a..017ded76ed 100644 --- a/src/modules/commander/esc_calibration.cpp +++ b/src/modules/commander/esc_calibration.cpp @@ -79,7 +79,7 @@ int do_esc_calibration(orb_advert_t *mavlink_log_pub, struct actuator_armed_s *a break; } else { - usleep(50000); + px4_usleep(50000); } } @@ -188,7 +188,7 @@ int do_esc_calibration(orb_advert_t *mavlink_log_pub, struct actuator_armed_s *a } } - usleep(50_ms); + px4_usleep(50_ms); } Out: diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index 3fc618fa7f..13ac8308f3 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -539,7 +539,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) } /* if there is a any preflight-check system response, let the barrage of messages through */ - usleep(200000); + px4_usleep(200000); if (res == PX4_OK) { calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name); @@ -551,7 +551,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) orb_unsubscribe(worker_data.sensor_correction_sub); /* give this message enough time to propagate */ - usleep(600000); + px4_usleep(600000); return res; } diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 58a439806c..966bd87bad 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -246,23 +246,23 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub) case calibrate_return_ok: /* if there is a any preflight-check system response, let the barrage of messages through */ - usleep(200000); + px4_usleep(200000); calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG, 100); - usleep(20000); + px4_usleep(20000); calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, sensor_name); - usleep(20000); + px4_usleep(20000); break; default: calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name); - usleep(20000); + px4_usleep(20000); break; } } /* give this message enough time to propagate */ - usleep(600000); + px4_usleep(600000); return result; } @@ -497,7 +497,7 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta calibration_log_info(worker_data->mavlink_log_pub, "[cal] %s side calibration: progress <%u>", detect_orientation_str(orientation), new_progress); - usleep(20000); + px4_usleep(20000); _last_mag_progress = new_progress; } @@ -519,7 +519,7 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta detect_orientation_str(orientation)); worker_data->done_count++; - usleep(20000); + px4_usleep(20000); calibration_log_info(worker_data->mavlink_log_pub, CAL_QGC_PROGRESS_MSG, progress_percentage(worker_data)); } @@ -559,7 +559,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) calibration_log_info(mavlink_log_pub, "[cal] %s side done, rotate to a different side", detect_orientation_str(static_cast<enum detect_orientation_return>(i))); - usleep(100000); + px4_usleep(100000); } } @@ -891,7 +891,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub) calibration_log_info(mavlink_log_pub, "[cal] mag #%u scale: x:%.2f y:%.2f z:%.2f", cur_mag, (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale); #endif - usleep(200000); + px4_usleep(200000); } } } diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp index cbcd8ece3f..6dd4951a28 100644 --- a/src/modules/commander/rc_calibration.cpp +++ b/src/modules/commander/rc_calibration.cpp @@ -54,7 +54,7 @@ int do_trim_calibration(orb_advert_t *mavlink_log_pub) { int sub_man = orb_subscribe(ORB_ID(manual_control_setpoint)); - usleep(400000); + px4_usleep(400000); struct manual_control_setpoint_s sp; bool changed; orb_check(sub_man, &changed); diff --git a/src/modules/commander/rc_check.cpp b/src/modules/commander/rc_check.cpp index 31c164874e..582e73503b 100644 --- a/src/modules/commander/rc_check.cpp +++ b/src/modules/commander/rc_check.cpp @@ -77,7 +77,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC_MAP_TRANS_SW PARAMETER MISSING."); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); map_fail_count++; } else { @@ -102,7 +102,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: PARAM %s MISSING.", rc_map_mandatory[j]); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); map_fail_count++; j++; continue; @@ -115,7 +115,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: %s >= NUMBER OF CHANNELS.", rc_map_mandatory[j]); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); map_fail_count++; } @@ -123,7 +123,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: mandatory %s is unmapped.", rc_map_mandatory[j]); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); map_fail_count++; } @@ -176,7 +176,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC%d_MIN < %u.", i + 1, RC_INPUT_LOWEST_MIN_US); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); } if (param_max > RC_INPUT_HIGHEST_MAX_US) { @@ -185,7 +185,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC%d_MAX > %u.", i + 1, RC_INPUT_HIGHEST_MAX_US); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); } if (param_trim < param_min) { @@ -194,7 +194,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC%d_TRIM < MIN (%d/%d).", i + 1, (int)param_trim, (int)param_min); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); } if (param_trim > param_max) { @@ -203,7 +203,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC%d_TRIM > MAX (%d/%d).", i + 1, (int)param_trim, (int)param_max); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); } /* assert deadzone is sane */ @@ -211,7 +211,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC ERROR: RC%d_DZ > %u.", i + 1, RC_INPUT_MAX_DEADZONE_US); } /* give system time to flush error message in case there are more */ - usleep(100000); + px4_usleep(100000); count++; } @@ -231,7 +231,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i (total_fail_count > 1) ? "s" : "", channels_failed, (channels_failed > 1) ? "s" : ""); } - usleep(100000); + px4_usleep(100000); } return total_fail_count + map_fail_count; diff --git a/src/modules/ekf2/ekf2_main.cpp b/src/modules/ekf2/ekf2_main.cpp index 002fb2a285..42716c5d53 100644 --- a/src/modules/ekf2/ekf2_main.cpp +++ b/src/modules/ekf2/ekf2_main.cpp @@ -727,7 +727,7 @@ void Ekf2::run() if (ret < 0) { // Poll error, sleep and try again - usleep(10000); + px4_usleep(10000); continue; } else if (ret == 0) { diff --git a/src/modules/events/temperature_calibration/task.cpp b/src/modules/events/temperature_calibration/task.cpp index 3f2afeb7ce..d8c3b97065 100644 --- a/src/modules/events/temperature_calibration/task.cpp +++ b/src/modules/events/temperature_calibration/task.cpp @@ -181,7 +181,7 @@ void TemperatureCalibration::task_main() // make sure the system updates the changed parameters param_notify_changes(); - usleep(300000); // wait a bit for the system to apply the parameters + px4_usleep(300000); // wait a bit for the system to apply the parameters hrt_abstime next_progress_output = hrt_absolute_time() + 1e6; @@ -205,7 +205,7 @@ void TemperatureCalibration::task_main() if (ret < 0) { // Poll error, sleep and try again - usleep(10000); + px4_usleep(10000); continue; } else if (ret == 0) { diff --git a/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp b/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp index fe2f12b0e7..3288ed8194 100644 --- a/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp +++ b/src/modules/gnd_att_control/GroundRoverAttitudeControl.cpp @@ -89,7 +89,7 @@ GroundRoverAttitudeControl::~GroundRoverAttitudeControl() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { @@ -403,7 +403,7 @@ int gnd_att_control_main(int argc, char *argv[]) /* avoid memory fragmentation by not exiting start handler until the task has fully started */ while (att_gnd_control::g_control == nullptr || !att_gnd_control::g_control->task_running()) { - usleep(50000); + px4_usleep(50000); printf("."); fflush(stdout); } diff --git a/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp b/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp index 4960b788e9..e3013956ca 100644 --- a/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp +++ b/src/modules/gnd_pos_control/GroundRoverPositionControl.cpp @@ -103,7 +103,7 @@ GroundRoverPositionControl::~GroundRoverPositionControl() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { @@ -523,7 +523,7 @@ int gnd_pos_control_main(int argc, char *argv[]) /* avoid memory fragmentation by not exiting start handler until the task has fully started */ while (gnd_control::g_control == nullptr || !gnd_control::g_control->task_running()) { - usleep(50000); + px4_usleep(50000); printf("."); fflush(stdout); } diff --git a/src/modules/landing_target_estimator/landing_target_estimator_main.cpp b/src/modules/landing_target_estimator/landing_target_estimator_main.cpp index af501bf6ce..db00255f6c 100644 --- a/src/modules/landing_target_estimator/landing_target_estimator_main.cpp +++ b/src/modules/landing_target_estimator/landing_target_estimator_main.cpp @@ -140,7 +140,7 @@ int landing_target_estimator_thread_main(int argc, char *argv[]) while (!thread_should_exit) { est.update(); - usleep(1000000 / landing_target_estimator_UPDATE_RATE_HZ); + px4_usleep(1000000 / landing_target_estimator_UPDATE_RATE_HZ); } PX4_DEBUG("exiting"); diff --git a/src/modules/logger/log_writer_file.cpp b/src/modules/logger/log_writer_file.cpp index a2c09fbc7f..435f8c1652 100644 --- a/src/modules/logger/log_writer_file.cpp +++ b/src/modules/logger/log_writer_file.cpp @@ -300,7 +300,7 @@ int LogWriterFile::write_message(LogType type, void *ptr, size_t size, uint64_t while ((ret = write(type, ptr, 0, dropout_start)) == -1) { unlock(); notify(); - usleep(3000); + px4_usleep(3000); lock(); } } @@ -314,7 +314,7 @@ int LogWriterFile::write_message(LogType type, void *ptr, size_t size, uint64_t while ((ret = write(type, uptr, write_size, 0)) == -1) { unlock(); notify(); - usleep(3000); + px4_usleep(3000); lock(); } diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index b626cf8e27..da171f2876 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -345,7 +345,7 @@ Mavlink::~Mavlink() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { @@ -465,7 +465,7 @@ Mavlink::destroy_all_instances() while (inst_to_del->_task_running) { printf("."); fflush(stdout); - usleep(10000); + px4_usleep(10000); iterations++; if (iterations > 1000) { @@ -701,7 +701,7 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, bool force_flow_ /* back off 1800 ms to avoid running into the USB setup timing */ while (_mode == MAVLINK_MODE_CONFIG && hrt_absolute_time() < 1800U * 1000U) { - usleep(50000); + px4_usleep(50000); } /* open uart */ @@ -734,7 +734,7 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, bool force_flow_ } } - usleep(100000); + px4_usleep(100000); _uart_fd = ::open(uart_name, O_RDWR | O_NOCTTY); } @@ -1457,7 +1457,7 @@ Mavlink::configure_stream_threadsafe(const char *stream_name, const float rate) if (!_task_should_exit) { /* wait for previous subscription completion */ while (_subscribe_to_stream != nullptr) { - usleep(MAIN_LOOP_DELAY / 2); + px4_usleep(MAIN_LOOP_DELAY / 2); } /* copy stream name */ @@ -1471,7 +1471,7 @@ Mavlink::configure_stream_threadsafe(const char *stream_name, const float rate) /* wait for subscription */ do { - usleep(MAIN_LOOP_DELAY / 2); + px4_usleep(MAIN_LOOP_DELAY / 2); } while (_subscribe_to_stream != nullptr); delete[] s; @@ -2280,7 +2280,7 @@ Mavlink::task_main(int argc, char *argv[]) while (!_task_should_exit) { /* main loop */ - usleep(_main_loop_delay); + px4_usleep(_main_loop_delay); perf_begin(_loop_perf); @@ -2667,28 +2667,28 @@ void Mavlink::check_radio_config() if (fs) { /* switch to AT command mode */ - usleep(1200000); + px4_usleep(1200000); fprintf(fs, "+++\n"); - usleep(1200000); + px4_usleep(1200000); if (_param_radio_id.get() > 0) { /* set channel */ fprintf(fs, "ATS3=%u\n", _param_radio_id.get()); - usleep(200000); + px4_usleep(200000); } else { /* reset to factory defaults */ fprintf(fs, "AT&F\n"); - usleep(200000); + px4_usleep(200000); } /* write config */ fprintf(fs, "AT&W"); - usleep(200000); + px4_usleep(200000); /* reboot */ fprintf(fs, "ATZ"); - usleep(200000); + px4_usleep(200000); // XXX NuttX suffers from a bug where // fclose() also closes the fd, not just @@ -2779,7 +2779,7 @@ Mavlink::start(int argc, char *argv[]) unsigned count = 0; while (ic == Mavlink::instance_count() && count < limit) { - ::usleep(sleeptime); + px4_usleep(sleeptime); count++; } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index c7875f37c1..a74712fdaf 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -2638,7 +2638,7 @@ MavlinkReceiver::receive_thread(void *arg) if (_mavlink->get_protocol() == UDP || _mavlink->get_protocol() == TCP) { // make sure mavlink app has booted before we start using the socket while (!_mavlink->boot_complete()) { - usleep(100000); + px4_usleep(100000); } fds[0].fd = _mavlink->get_socket_fd(); @@ -2662,7 +2662,7 @@ MavlinkReceiver::receive_thread(void *arg) /* non-blocking read. read may return negative values */ if ((nread = ::read(fds[0].fd, buf, sizeof(buf))) < (ssize_t)character_count) { const unsigned sleeptime = character_count * 1000000 / (_mavlink->get_baudrate() / 10); - usleep(sleeptime); + px4_usleep(sleeptime); } } diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 464e96ff81..ec2a07c218 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -849,7 +849,7 @@ MulticopterAttitudeControl::run() if (pret < 0) { PX4_ERR("poll error %d, %d", pret, errno); /* sleep a bit before next try */ - usleep(100000); + px4_usleep(100000); continue; } diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 70045453e2..6510373a98 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -234,7 +234,7 @@ Navigator::run() } else if (pret < 0) { /* this is undesirable but not much we can do - might want to flag unhappy status */ PX4_ERR("poll error %d, %d", pret, errno); - usleep(10000); + px4_usleep(10000); continue; } else { diff --git a/src/modules/replay/replay_main.cpp b/src/modules/replay/replay_main.cpp index 21057db0eb..b76fe1a01d 100644 --- a/src/modules/replay/replay_main.cpp +++ b/src/modules/replay/replay_main.cpp @@ -875,7 +875,7 @@ uint64_t Replay::handleTopicDelay(uint64_t next_file_time, uint64_t timestamp_of // if some topics have a timestamp smaller than the log file start, publish them immediately if (cur_time < publish_timestamp && next_file_time > _file_start_time) { - usleep(publish_timestamp - cur_time); + px4_usleep(publish_timestamp - cur_time); } return publish_timestamp; @@ -948,7 +948,7 @@ bool ReplayEkf2::handleTopicUpdate(Subscription &sub, void *data, std::ifstream // introduce some breaks to make sure the logger can keep up if (++_topic_counter == 50) { - usleep(1000); + px4_usleep(1000); _topic_counter = 0; } diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index a32d7db128..1d6291158e 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -641,7 +641,7 @@ Sensors::run() _voted_sensors_update.initialize_sensors(); } - usleep(1000); + px4_usleep(1000); continue; } diff --git a/src/modules/simulator/airspeedsim/airspeedsim.cpp b/src/modules/simulator/airspeedsim/airspeedsim.cpp index fb21757b46..c3b0cbda4e 100644 --- a/src/modules/simulator/airspeedsim/airspeedsim.cpp +++ b/src/modules/simulator/airspeedsim/airspeedsim.cpp @@ -271,7 +271,7 @@ AirspeedSim::read(cdev::file_t *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(_conversion_interval); + px4_usleep(_conversion_interval); /* run the collection phase */ if (OK != collect()) { diff --git a/src/modules/simulator/gpssim/gpssim.cpp b/src/modules/simulator/gpssim/gpssim.cpp index a2c17ecf2a..700df26a5d 100644 --- a/src/modules/simulator/gpssim/gpssim.cpp +++ b/src/modules/simulator/gpssim/gpssim.cpp @@ -198,7 +198,7 @@ GPSSIM::~GPSSIM() /* spin waiting for the task to stop */ for (unsigned i = 0; (i < 10) && (_task != -1); i++) { /* give it another 100ms */ - usleep(100000); + px4_usleep(100000); } /* well, kill it anyway, though this will probably crash */ @@ -301,7 +301,7 @@ GPSSIM::receive(int timeout) } else { - usleep(timeout); + px4_usleep(timeout); return 0; } } @@ -371,7 +371,7 @@ GPSSIM::print_info() print_message(_report_gps_pos); } - usleep(100000); + px4_usleep(100000); } void diff --git a/src/modules/simulator/simulator.cpp b/src/modules/simulator/simulator.cpp index 9188830901..077a6ca837 100644 --- a/src/modules/simulator/simulator.cpp +++ b/src/modules/simulator/simulator.cpp @@ -220,7 +220,7 @@ extern "C" { break; } else { - usleep(100000); + px4_usleep(100000); } } diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index d860fd57eb..d58430daf2 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -336,7 +336,7 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish) unsigned usleep_delay = (sysdelay - min_delay) / _realtime_factor; // extend by the realtime factor to avoid drift - usleep(usleep_delay); + px4_usleep(usleep_delay); hrt_stop_delay_delta(exact_delay); px4_sim_stop_delay(); } @@ -838,7 +838,7 @@ void Simulator::pollForMAVLinkMessages(bool publish, int udp_port) if (pret < 0) { PX4_WARN("simulator mavlink: poll error %d, %d", pret, errno); // sleep a bit before next try - usleep(100000); + px4_usleep(100000); continue; } diff --git a/src/modules/uORB/uORBDeviceMaster.cpp b/src/modules/uORB/uORBDeviceMaster.cpp index bd97e951e5..160aec9584 100644 --- a/src/modules/uORB/uORBDeviceMaster.cpp +++ b/src/modules/uORB/uORBDeviceMaster.cpp @@ -316,7 +316,7 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters) } } - usleep(200000); + px4_usleep(200000); } #endif diff --git a/src/modules/uORB/uORBDeviceNode.cpp b/src/modules/uORB/uORBDeviceNode.cpp index e176598722..e50b9ccff3 100644 --- a/src/modules/uORB/uORBDeviceNode.cpp +++ b/src/modules/uORB/uORBDeviceNode.cpp @@ -593,7 +593,7 @@ uORB::DeviceNode::appears_updated(SubscriberData *sd) /* block if in simulation mode */ while (px4_sim_delay_enabled()) { - usleep(100); + px4_usleep(100); } /* assume it doesn't look updated */ diff --git a/src/modules/uORB/uORB_tests/uORBTest_UnitTest.cpp b/src/modules/uORB/uORB_tests/uORBTest_UnitTest.cpp index 621b11cd62..9e729bf055 100644 --- a/src/modules/uORB/uORB_tests/uORBTest_UnitTest.cpp +++ b/src/modules/uORB/uORB_tests/uORBTest_UnitTest.cpp @@ -455,12 +455,12 @@ int uORBTest::UnitTest::pub_test_multi2_main() } } - usleep(100 * 1000); + px4_usleep(100 * 1000); int message_counter = 0, num_messages = 50 * num_instances; while (message_counter++ < num_messages) { - usleep(2); //make sure the timestamps are different + px4_usleep(2); //make sure the timestamps are different orb_advert_t &pub = orb_pub[data_next_idx]; data_topic.time = hrt_absolute_time(); @@ -472,11 +472,11 @@ int uORBTest::UnitTest::pub_test_multi2_main() data_next_idx = (data_next_idx + 1) % num_instances; if (data_next_idx == 0) { - usleep(50 * 1000); + px4_usleep(50 * 1000); } } - usleep(100 * 1000); + px4_usleep(100 * 1000); _thread_should_exit = true; for (int i = 0; i < num_instances; ++i) { @@ -528,9 +528,9 @@ int uORBTest::UnitTest::test_multi2() // Relax timing requirement for Darwin CI system #ifdef __PX4_DARWIN - usleep(10000); + px4_usleep(10000); #else - usleep(1000); + px4_usleep(1000); #endif if (last_time >= msg.time && last_time != 0) { @@ -767,11 +767,11 @@ int uORBTest::UnitTest::pub_test_queue_main() } message_counter += burst_counter; - usleep(20 * 1000); //give subscriber a chance to catch up + px4_usleep(20 * 1000); //give subscriber a chance to catch up } _num_messages_sent = t.val; - usleep(100 * 1000); + px4_usleep(100 * 1000); _thread_should_exit = true; orb_unadvertise(ptopic); diff --git a/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp b/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp index bb54d92bbf..83442f68aa 100644 --- a/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp +++ b/src/modules/uORB/uORB_tests/uORBTest_UnitTest.hpp @@ -162,7 +162,7 @@ int uORBTest::UnitTest::latency_test(orb_id_t T, bool print) } /* simulate >800 Hz system operation */ - usleep(1000); + px4_usleep(1000); } if (pubsub_task < 0) { diff --git a/src/modules/vmount/vmount.cpp b/src/modules/vmount/vmount.cpp index e82e745ddd..0589f9be10 100644 --- a/src/modules/vmount/vmount.cpp +++ b/src/modules/vmount/vmount.cpp @@ -387,7 +387,7 @@ static int vmount_thread_main(int argc, char *argv[]) } else { //wait for parameter changes. We still need to wake up regularily to check for thread exit requests - usleep(1e6); + px4_usleep(1e6); } if (test_input && test_input->finished()) { @@ -478,7 +478,7 @@ int vmount_main(int argc, char *argv[]) int counter = 0; while (!thread_running && vmount_task >= 0) { - usleep(5000); + px4_usleep(5000); if (++counter >= 100) { break; @@ -504,7 +504,7 @@ int vmount_main(int argc, char *argv[]) thread_should_exit = true; while (thread_running) { - usleep(100000); + px4_usleep(100000); } return 0; diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp index 1180875cc2..3032179f10 100644 --- a/src/modules/vtol_att_control/vtol_att_control_main.cpp +++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp @@ -120,7 +120,7 @@ VtolAttitudeControl::~VtolAttitudeControl() do { /* wait 20ms */ - usleep(20000); + px4_usleep(20000); /* if we have given up, kill it */ if (++i > 50) { @@ -590,7 +590,7 @@ void VtolAttitudeControl::task_main() if (pret < 0) { PX4_ERR("poll error %d, %d", pret, errno); /* sleep a bit before next try */ - usleep(100000); + px4_usleep(100000); continue; } diff --git a/src/platforms/apps.cpp.in b/src/platforms/apps.cpp.in index 123a138c4e..f768845d99 100644 --- a/src/platforms/apps.cpp.in +++ b/src/platforms/apps.cpp.in @@ -1,4 +1,5 @@ /* definitions of builtin command list - automatically generated, do not edit */ +#include "px4_time.h" #include "px4_posix.h" #include "px4_log.h" @@ -86,7 +87,7 @@ int sleep_main(int argc, char *argv[]) unsigned long usecs = 1000000UL * atol(argv[1]); printf("Sleeping for %s s; (%lu us).\n", argv[1], usecs); - usleep(usecs); + px4_usleep(usecs); return 0; } diff --git a/src/platforms/common/work_queue/hrt_thread.c b/src/platforms/common/work_queue/hrt_thread.c index 700daa215a..e17b90ddba 100644 --- a/src/platforms/common/work_queue/hrt_thread.c +++ b/src/platforms/common/work_queue/hrt_thread.c @@ -217,7 +217,7 @@ static void hrt_work_process() /* might sleep less if a signal received and new item was queued */ //PX4_INFO("Sleeping for %u usec", next); - usleep(next); + px4_usleep(next); } /**************************************************************************** diff --git a/src/platforms/common/work_queue/work_thread.c b/src/platforms/common/work_queue/work_thread.c index 806c2179d7..a5c3cd873f 100644 --- a/src/platforms/common/work_queue/work_thread.c +++ b/src/platforms/common/work_queue/work_thread.c @@ -182,7 +182,7 @@ static void work_process(struct wqueue_s *wqueue, int lock_id) */ work_unlock(lock_id); - usleep(next); + px4_usleep(next); } /**************************************************************************** diff --git a/src/platforms/px4_module.h b/src/platforms/px4_module.h index bd362ecd2d..0961ffb4c9 100644 --- a/src/platforms/px4_module.h +++ b/src/platforms/px4_module.h @@ -41,6 +41,7 @@ #include <unistd.h> #include <stdbool.h> +#include <px4_time.h> #include <px4_log.h> #include <px4_tasks.h> #include <systemlib/px4_macros.h> @@ -236,7 +237,7 @@ public: do { unlock_module(); - usleep(20000); // 20 ms + px4_usleep(20000); // 20 ms lock_module(); if (++i > 100 && _task_id != -1) { // wait at most 2 sec @@ -369,7 +370,7 @@ protected: do { /* Wait up to 1s. */ - usleep(2500); + px4_usleep(2500); } while (!_object && ++i < 400); diff --git a/src/platforms/px4_nodehandle.h b/src/platforms/px4_nodehandle.h index 9ae11474de..faf5b0158b 100644 --- a/src/platforms/px4_nodehandle.h +++ b/src/platforms/px4_nodehandle.h @@ -39,6 +39,7 @@ #pragma once /* includes for all platforms */ +#include "px4_time.h" #include "px4_subscriber.h" #include "px4_publisher.h" #include "px4_middleware.h" @@ -274,7 +275,7 @@ public: /* Only continue in the loop if the nodehandle has subscriptions */ if (_sub_min_interval == nullptr) { - usleep(timeout_ms * 1000); + px4_usleep(timeout_ms * 1000); continue; } diff --git a/src/platforms/px4_time.h b/src/platforms/px4_time.h index 9324151cd0..ef22d7db6c 100644 --- a/src/platforms/px4_time.h +++ b/src/platforms/px4_time.h @@ -34,4 +34,6 @@ __END_DECLS #define px4_clock_gettime clock_gettime #define px4_clock_settime clock_settime +#define px4_usleep system_usleep + #endif diff --git a/src/systemcmds/bl_update/bl_update.c b/src/systemcmds/bl_update/bl_update.c index b7b924b374..86ee48afab 100644 --- a/src/systemcmds/bl_update/bl_update.c +++ b/src/systemcmds/bl_update/bl_update.c @@ -154,7 +154,7 @@ bl_update_main(int argc, char *argv[]) } PX4_INFO("image validated, erasing bootloader..."); - usleep(10000); + px4_usleep(10000); /* prevent other tasks from running while we do this */ sched_lock(); @@ -232,7 +232,7 @@ setopt(void) /* program the new option value */ *optcr = (*optcr & ~opt_mask) | opt_bits | (1 << 1); - usleep(1000); + px4_usleep(1000); if ((*optcr & opt_mask) == opt_bits) { PX4_INFO("option bits set"); diff --git a/src/systemcmds/esc_calib/esc_calib.c b/src/systemcmds/esc_calib/esc_calib.c index 39220a3ff1..cdb135ac6e 100644 --- a/src/systemcmds/esc_calib/esc_calib.c +++ b/src/systemcmds/esc_calib/esc_calib.c @@ -210,7 +210,7 @@ esc_calib_main(int argc, char *argv[]) orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, act_sub, &actuators); /* wait 50 ms */ - usleep(50000); + px4_usleep(50000); /* now expect nothing changed on that topic */ bool orb_updated; @@ -261,7 +261,7 @@ esc_calib_main(int argc, char *argv[]) } /* rate limit to ~ 20 Hz */ - usleep(50000); + px4_usleep(50000); } /* open for ioctl only */ @@ -338,7 +338,7 @@ esc_calib_main(int argc, char *argv[]) } /* rate limit to ~ 20 Hz */ - usleep(50000); + px4_usleep(50000); } printf("Low PWM set: %d\n" @@ -378,7 +378,7 @@ esc_calib_main(int argc, char *argv[]) } /* rate limit to ~ 20 Hz */ - usleep(50000); + px4_usleep(50000); } /* disarm */ diff --git a/src/systemcmds/led_control/led_control.cpp b/src/systemcmds/led_control/led_control.cpp index 1981e4c267..94f4e274ed 100644 --- a/src/systemcmds/led_control/led_control.cpp +++ b/src/systemcmds/led_control/led_control.cpp @@ -112,7 +112,7 @@ static void run_led_test1() led_control.priority = led_control_s::MAX_PRIORITY; publish_led_control(led_control); - usleep(200 * 1000); + px4_usleep(200 * 1000); // generate some pattern for (int round = led_control_s::COLOR_RED; round <= led_control_s::COLOR_WHITE; ++round) { @@ -121,25 +121,25 @@ static void run_led_test1() led_control.mode = led_control_s::MODE_ON; led_control.color = round; publish_led_control(led_control); - usleep(80 * 1000); + px4_usleep(80 * 1000); } - usleep(100 * 1000); + px4_usleep(100 * 1000); led_control.led_mask = 0xff; for (int i = 0; i < 3; ++i) { led_control.mode = led_control_s::MODE_ON; publish_led_control(led_control); - usleep(100 * 1000); + px4_usleep(100 * 1000); led_control.mode = led_control_s::MODE_OFF; publish_led_control(led_control); - usleep(100 * 1000); + px4_usleep(100 * 1000); } - usleep(200 * 1000); + px4_usleep(200 * 1000); } - usleep(500 * 1000); + px4_usleep(500 * 1000); // reset led_control.led_mask = 0xff; diff --git a/src/systemcmds/mixer/mixer.cpp b/src/systemcmds/mixer/mixer.cpp index 9bc520777f..7524c7b30e 100644 --- a/src/systemcmds/mixer/mixer.cpp +++ b/src/systemcmds/mixer/mixer.cpp @@ -133,7 +133,7 @@ static int load(const char *devname, const char *fname, bool append) { // sleep a while to ensure device has been set up - usleep(20000); + px4_usleep(20000); int dev; diff --git a/src/systemcmds/motor_ramp/motor_ramp.cpp b/src/systemcmds/motor_ramp/motor_ramp.cpp index a7b0a4a882..cf30b76b7c 100644 --- a/src/systemcmds/motor_ramp/motor_ramp.cpp +++ b/src/systemcmds/motor_ramp/motor_ramp.cpp @@ -273,7 +273,7 @@ int prepare(int fd, unsigned long *max_channels) orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, act_sub, &actuators); /* wait 50 ms */ - usleep(50000); + px4_usleep(50000); /* now expect nothing changed on that topic */ bool orb_updated; @@ -409,7 +409,7 @@ int motor_ramp_thread_main(int argc, char *argv[]) } // rate limit - usleep(2000); + px4_usleep(2000); } if (fd >= 0) { diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c index 8c476e91f8..fdae55edcd 100644 --- a/src/systemcmds/mtd/24xxxx_mtd.c +++ b/src/systemcmds/mtd/24xxxx_mtd.c @@ -51,6 +51,7 @@ ************************************************************************************/ #include <px4_config.h> +#include <px4_time.h> #include <sys/types.h> #include <stdint.h> @@ -228,7 +229,7 @@ static int at24c_eraseall(FAR struct at24c_dev_s *priv) while (I2C_TRANSFER(priv->dev, &msgv[0], 1) < 0) { fwarn("erase stall\n"); - usleep(10000); + px4_usleep(10000); } } @@ -341,7 +342,7 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, } finfo("read stall"); - usleep(1000); + px4_usleep(1000); /* We should normally only be here on the first read after * a write. @@ -430,7 +431,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t } finfo("write stall"); - usleep(1000); + px4_usleep(1000); /* We expect to see a number of retries per write cycle as we * poll for write completion. diff --git a/src/systemcmds/pwm/pwm.cpp b/src/systemcmds/pwm/pwm.cpp index fc1e1d356e..e01e0ca389 100644 --- a/src/systemcmds/pwm/pwm.cpp +++ b/src/systemcmds/pwm/pwm.cpp @@ -703,7 +703,7 @@ pwm_main(int argc, char *argv[]) /* Delay longer than the max Oneshot duration */ - usleep(2542); + px4_usleep(2542); #ifdef __PX4_NUTTX /* Trigger all timer's channels in Oneshot mode to fire @@ -828,13 +828,13 @@ err_out_no_test: } if (phase == 1) { - usleep(steps_timings_us[steps_timing_index] / phase_maxcount); + px4_usleep(steps_timings_us[steps_timing_index] / phase_maxcount); } else if (phase == 0) { - usleep(50000); + px4_usleep(50000); } else if (phase == 2) { - usleep(50000); + px4_usleep(50000); } else { break; diff --git a/src/systemcmds/reboot/reboot.c b/src/systemcmds/reboot/reboot.c index 92d8389d36..56d7c1f42f 100644 --- a/src/systemcmds/reboot/reboot.c +++ b/src/systemcmds/reboot/reboot.c @@ -107,7 +107,7 @@ int reboot_main(int argc, char *argv[]) return -1; } - while (1) { usleep(1); } // this command should not return on success + while (1) { px4_usleep(1); } // this command should not return on success return 0; } diff --git a/src/systemcmds/tests/hrt_test/hrt_test.cpp b/src/systemcmds/tests/hrt_test/hrt_test.cpp index 2c220af492..00fd2e9952 100644 --- a/src/systemcmds/tests/hrt_test/hrt_test.cpp +++ b/src/systemcmds/tests/hrt_test/hrt_test.cpp @@ -70,7 +70,7 @@ int HRTTest::main() appState.setRunning(true); hrt_abstime t = hrt_absolute_time(); - usleep(1000000); + px4_usleep(1000000); hrt_abstime elt = hrt_elapsed_time(&t); PX4_INFO("Elapsed time %llu in 1 sec (usleep)\n", (unsigned long long)elt); PX4_INFO("Start time %llu\n", (unsigned long long)t); diff --git a/src/systemcmds/tests/test_adc.c b/src/systemcmds/tests/test_adc.c index b507b323f7..99252a2dd4 100644 --- a/src/systemcmds/tests/test_adc.c +++ b/src/systemcmds/tests/test_adc.c @@ -36,6 +36,7 @@ * Test for the analog to digital converter. */ +#include <px4_time.h> #include <px4_config.h> #include <px4_posix.h> #include <px4_log.h> @@ -78,7 +79,7 @@ int test_adc(int argc, char *argv[]) } printf("\n"); - usleep(150000); + px4_usleep(150000); } printf("\t ADC test successful.\n"); diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c index 10668d99d7..a70f9af256 100644 --- a/src/systemcmds/tests/test_dataman.c +++ b/src/systemcmds/tests/test_dataman.c @@ -108,7 +108,7 @@ task_main(int argc, char *argv[]) PX4_INFO("task %d: %.0f%%", my_id, (double)i * 100.0f / NUM_MISSIONS_TEST); } - usleep(rand() & ((64 * 1024) - 1)); + px4_usleep(rand() & ((64 * 1024) - 1)); } hrt_abstime rstart = hrt_absolute_time(); diff --git a/src/systemcmds/tests/test_hott_telemetry.c b/src/systemcmds/tests/test_hott_telemetry.c index b9b01ff44a..5e863773c6 100644 --- a/src/systemcmds/tests/test_hott_telemetry.c +++ b/src/systemcmds/tests/test_hott_telemetry.c @@ -43,6 +43,7 @@ * Included Files ****************************************************************************/ +#include <px4_time.h> #include <px4_config.h> #include <px4_defines.h> #include <px4_log.h> @@ -220,11 +221,11 @@ int test_hott_telemetry(int argc, char *argv[]) 0x00, 0x00, 0x00, 0x7d, 0x12 }; - usleep(5000); + px4_usleep(5000); for (unsigned int i = 0; i < sizeof(response); i++) { write(fd, &response[i], 1); - usleep(1000); + px4_usleep(1000); } PX4_INFO("PASS: Response sent to the HoTT receiver device. Voltage should now show 2.5V."); diff --git a/src/systemcmds/tests/test_hrt.cpp b/src/systemcmds/tests/test_hrt.cpp index e64e4f3104..8f51804b9d 100644 --- a/src/systemcmds/tests/test_hrt.cpp +++ b/src/systemcmds/tests/test_hrt.cpp @@ -191,7 +191,7 @@ int test_hrt(int argc, char *argv[]) for (i = 0; i < 10; i++) { prev = hrt_absolute_time(); gettimeofday(&tv1, nullptr); - usleep(100000); + px4_usleep(100000); now = hrt_absolute_time(); gettimeofday(&tv2, nullptr); printf("%lu (%lu/%lu), %lu (%lu/%lu), %lu\n", @@ -201,7 +201,7 @@ int test_hrt(int argc, char *argv[]) fflush(stdout); } - usleep(1000000); + px4_usleep(1000000); printf("one-second ticks\n"); @@ -209,7 +209,7 @@ int test_hrt(int argc, char *argv[]) hrt_call_after(&call, 1000000, nullptr, nullptr); while (!hrt_called(&call)) { - usleep(1000); + px4_usleep(1000); } printf("tick\n"); diff --git a/src/systemcmds/tests/test_hysteresis.cpp b/src/systemcmds/tests/test_hysteresis.cpp index 84f2ea49a0..1af3e5b9e5 100644 --- a/src/systemcmds/tests/test_hysteresis.cpp +++ b/src/systemcmds/tests/test_hysteresis.cpp @@ -69,7 +69,7 @@ bool HysteresisTest::_zero_case() ut_assert_true(hysteresis.get_state()); // A wait won't change anything. - usleep(1000 * f); + px4_usleep(1000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); @@ -86,20 +86,20 @@ bool HysteresisTest::_change_after_time() // Change to true. hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(4000 * f); + px4_usleep(4000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); - usleep(2000 * f); + px4_usleep(2000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); // Change back to false. hysteresis.set_state_and_update(false); ut_assert_true(hysteresis.get_state()); - usleep(1000 * f); + px4_usleep(1000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); @@ -115,10 +115,10 @@ bool HysteresisTest::_hysteresis_changed() // Change to true. hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); @@ -128,10 +128,10 @@ bool HysteresisTest::_hysteresis_changed() // Change back to false. hysteresis.set_state_and_update(false); ut_assert_true(hysteresis.get_state()); - usleep(7000 * f); + px4_usleep(7000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); - usleep(5000 * f); + px4_usleep(5000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); @@ -147,20 +147,20 @@ bool HysteresisTest::_change_after_multiple_sets() // Change to true. hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.set_state_and_update(true); ut_assert_true(hysteresis.get_state()); // Change to false. hysteresis.set_state_and_update(false); ut_assert_true(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.set_state_and_update(false); ut_assert_true(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.set_state_and_update(false); ut_assert_false(hysteresis.get_state()); @@ -175,23 +175,23 @@ bool HysteresisTest::_take_change_back() // Change to true. hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); // Change your mind to false. hysteresis.set_state_and_update(false); ut_assert_false(hysteresis.get_state()); - usleep(6000 * f); + px4_usleep(6000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); // And true again hysteresis.set_state_and_update(true); ut_assert_false(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.update(); ut_assert_false(hysteresis.get_state()); - usleep(3000 * f); + px4_usleep(3000 * f); hysteresis.update(); ut_assert_true(hysteresis.get_state()); diff --git a/src/systemcmds/tests/test_led.c b/src/systemcmds/tests/test_led.c index 72830a2e90..d17cd74d23 100644 --- a/src/systemcmds/tests/test_led.c +++ b/src/systemcmds/tests/test_led.c @@ -35,6 +35,7 @@ * Included Files ****************************************************************************/ +#include <px4_time.h> #include <px4_config.h> #include <px4_posix.h> @@ -120,7 +121,7 @@ int test_led(int argc, char *argv[]) } ledon = !ledon; - usleep(60000); + px4_usleep(60000); } /* Go back to default */ diff --git a/src/systemcmds/tests/test_microbench_hrt.cpp b/src/systemcmds/tests/test_microbench_hrt.cpp index 80d917280c..8e3410f473 100644 --- a/src/systemcmds/tests/test_microbench_hrt.cpp +++ b/src/systemcmds/tests/test_microbench_hrt.cpp @@ -65,7 +65,7 @@ void unlock() } #define PERF(name, op, count) do { \ - usleep(1000); \ + px4_usleep(1000); \ reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ diff --git a/src/systemcmds/tests/test_microbench_math.cpp b/src/systemcmds/tests/test_microbench_math.cpp index a3d50f5adf..6e005c94c8 100644 --- a/src/systemcmds/tests/test_microbench_math.cpp +++ b/src/systemcmds/tests/test_microbench_math.cpp @@ -65,7 +65,7 @@ void unlock() } #define PERF(name, op, count) do { \ - usleep(1000); \ + px4_usleep(1000); \ reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ diff --git a/src/systemcmds/tests/test_microbench_matrix.cpp b/src/systemcmds/tests/test_microbench_matrix.cpp index 2cd7107c77..b8b83a2ee6 100644 --- a/src/systemcmds/tests/test_microbench_matrix.cpp +++ b/src/systemcmds/tests/test_microbench_matrix.cpp @@ -67,7 +67,7 @@ void unlock() } #define PERF(name, op, count) do { \ - usleep(1000); \ + px4_usleep(1000); \ reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ diff --git a/src/systemcmds/tests/test_microbench_uorb.cpp b/src/systemcmds/tests/test_microbench_uorb.cpp index 9d9faff226..c1ac196daf 100644 --- a/src/systemcmds/tests/test_microbench_uorb.cpp +++ b/src/systemcmds/tests/test_microbench_uorb.cpp @@ -70,7 +70,7 @@ void unlock() } #define PERF(name, op, count) do { \ - usleep(1000); \ + px4_usleep(1000); \ reset(); \ perf_counter_t p = perf_alloc(PC_ELAPSED, name); \ for (int i = 0; i < count; i++) { \ diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp index 609b4a58f5..c84a30b6c6 100644 --- a/src/systemcmds/tests/test_mixer.cpp +++ b/src/systemcmds/tests/test_mixer.cpp @@ -451,7 +451,7 @@ bool MixerTest::mixerTest() } } - usleep(sleep_quantum_us); + px4_usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { @@ -516,7 +516,7 @@ bool MixerTest::mixerTest() } } - usleep(sleep_quantum_us); + px4_usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { @@ -566,7 +566,7 @@ bool MixerTest::mixerTest() } } - usleep(sleep_quantum_us); + px4_usleep(sleep_quantum_us); sleepcount++; if (sleepcount % 10 == 0) { diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c index b6074c2559..896c961445 100644 --- a/src/systemcmds/tests/test_mount.c +++ b/src/systemcmds/tests/test_mount.c @@ -151,7 +151,7 @@ test_mount(int argc, char *argv[]) PX4_INFO("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC"); fsync(fileno(stdout)); fsync(fileno(stderr)); - usleep(20000); + px4_usleep(20000); } } @@ -186,7 +186,7 @@ test_mount(int argc, char *argv[]) printf("unpower the system immediately (within 0.5s) when the hash (#) sign appears\n"); fsync(fileno(stdout)); fsync(fileno(stderr)); - usleep(50000); + px4_usleep(50000); for (unsigned a = 0; a < alignments; a++) { @@ -236,7 +236,7 @@ test_mount(int argc, char *argv[]) printf("."); fsync(fileno(stdout)); fsync(fileno(stderr)); - usleep(200000); + px4_usleep(200000); px4_close(fd); fd = px4_open(PX4_STORAGEDIR "/testfile", O_RDONLY); @@ -282,7 +282,7 @@ test_mount(int argc, char *argv[]) fsync(fileno(stdout)); fsync(fileno(stderr)); - usleep(20000); + px4_usleep(20000); close(cmd_fd); @@ -290,7 +290,7 @@ test_mount(int argc, char *argv[]) PX4_INFO("Iteration done, rebooting.."); fsync(fileno(stdout)); fsync(fileno(stderr)); - usleep(50000); + px4_usleep(50000); px4_systemreset(false); /* never going to get here */ diff --git a/src/systemcmds/tests/test_ppm_loopback.c b/src/systemcmds/tests/test_ppm_loopback.c index 23023b059f..10e264bfa4 100644 --- a/src/systemcmds/tests/test_ppm_loopback.c +++ b/src/systemcmds/tests/test_ppm_loopback.c @@ -37,6 +37,7 @@ * */ +#include <px4_time.h> #include <px4_config.h> #include <sys/types.h> @@ -136,7 +137,7 @@ int test_ppm_loopback(int argc, char *argv[]) /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */ struct input_rc_s rc_input; orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input); - usleep(100000); + px4_usleep(100000); /* open PPM input and expect values close to the output values */ diff --git a/src/systemcmds/tests/test_rc.c b/src/systemcmds/tests/test_rc.c index 723af3d88c..d7f948442a 100644 --- a/src/systemcmds/tests/test_rc.c +++ b/src/systemcmds/tests/test_rc.c @@ -67,7 +67,7 @@ int test_rc(int argc, char *argv[]) struct input_rc_s rc_input; struct input_rc_s rc_last; orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input); - usleep(100000); + px4_usleep(100000); /* open PPM input and expect values close to the output values */ diff --git a/src/systemcmds/tests/test_sensors.c b/src/systemcmds/tests/test_sensors.c index 41c2fef1d8..20fe551cb3 100644 --- a/src/systemcmds/tests/test_sensors.c +++ b/src/systemcmds/tests/test_sensors.c @@ -38,6 +38,7 @@ * @author Lorenz Meier <lm@inf.ethz.ch> */ +#include <px4_time.h> #include <px4_config.h> #include <px4_posix.h> @@ -101,7 +102,7 @@ accel(int argc, char *argv[], const char *path) } /* wait at least 100ms, sensor should have data after no more than 20ms */ - usleep(100000); + px4_usleep(100000); /* read data - expect samples */ ret = px4_read(fd, &buf, sizeof(buf)); @@ -151,7 +152,7 @@ gyro(int argc, char *argv[], const char *path) } /* wait at least 5 ms, sensor should have data after that */ - usleep(5000); + px4_usleep(5000); /* read data - expect samples */ ret = px4_read(fd, &buf, sizeof(buf)); @@ -196,7 +197,7 @@ mag(int argc, char *argv[], const char *path) } /* wait at least 5 ms, sensor should have data after that */ - usleep(5000); + px4_usleep(5000); /* read data - expect samples */ ret = px4_read(fd, &buf, sizeof(buf)); @@ -241,7 +242,7 @@ baro(int argc, char *argv[], const char *path) } /* wait at least 5 ms, sensor should have data after that */ - usleep(5000); + px4_usleep(5000); /* read data - expect samples */ ret = px4_read(fd, &buf, sizeof(buf)); diff --git a/src/systemcmds/tests/test_servo.c b/src/systemcmds/tests/test_servo.c index a1980ce11e..27f34967c9 100644 --- a/src/systemcmds/tests/test_servo.c +++ b/src/systemcmds/tests/test_servo.c @@ -37,6 +37,7 @@ * */ +#include <px4_time.h> #include <px4_config.h> #include <sys/types.h> @@ -113,7 +114,7 @@ int test_servo(int argc, char *argv[]) goto out; } - usleep(5000000); + px4_usleep(5000000); printf("Advancing channel 0 to 1500\n"); result = ioctl(fd, PWM_SERVO_SET(0), 1500); printf("Advancing channel 1 to 1800\n"); diff --git a/src/systemcmds/tests/test_sleep.c b/src/systemcmds/tests/test_sleep.c index 9f4536c34d..addc7195d7 100644 --- a/src/systemcmds/tests/test_sleep.c +++ b/src/systemcmds/tests/test_sleep.c @@ -35,6 +35,7 @@ * Included Files ****************************************************************************/ +#include <px4_time.h> #include <px4_config.h> #include <px4_defines.h> @@ -57,7 +58,7 @@ int test_sleep(int argc, char *argv[]) fflush(stdout); for (unsigned int i = 0; i < nsleeps; i++) { - usleep(100000); + px4_usleep(100000); } printf("\t Sleep test successful.\n"); diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c index fccf3fd705..b5cebc29d8 100644 --- a/src/systemcmds/top/top.c +++ b/src/systemcmds/top/top.c @@ -121,7 +121,7 @@ top_main(int argc, char *argv[]) } } - usleep(200000); + px4_usleep(200000); } curr_time = hrt_absolute_time(); diff --git a/src/systemcmds/topic_listener/listener_main.cpp b/src/systemcmds/topic_listener/listener_main.cpp index 99efcada91..17d4b40c47 100644 --- a/src/systemcmds/topic_listener/listener_main.cpp +++ b/src/systemcmds/topic_listener/listener_main.cpp @@ -69,7 +69,7 @@ void listener(listener_print_topic_cb cb, const orb_id_t &id, unsigned num_msgs, updated = true; } else { - usleep(500); + px4_usleep(500); } if (updated) { diff --git a/src/systemcmds/tune_control/tune_control.cpp b/src/systemcmds/tune_control/tune_control.cpp index 326d6cd7d3..cd1a69a176 100644 --- a/src/systemcmds/tune_control/tune_control.cpp +++ b/src/systemcmds/tune_control/tune_control.cpp @@ -207,7 +207,7 @@ tune_control_main(int argc, char *argv[]) tune_control.silence = (uint32_t)silence; tune_control.strength = (uint8_t)strength; publish_tune_control(tune_control); - usleep(duration + silence); + px4_usleep(duration + silence); exit_counter++; // exit if the loop is doing too many iterations @@ -237,7 +237,7 @@ tune_control_main(int argc, char *argv[]) while (tunes.get_next_tune(frequency, duration, silence, strength) > 0) { PX4_INFO("frequency: %d, duration %d, silence %d, strength%d", frequency, duration, silence, strength); - usleep(500000); + px4_usleep(500000); exit_counter++; // exit if the loop is doing too many iterations @@ -256,7 +256,7 @@ tune_control_main(int argc, char *argv[]) publish_tune_control(tune_control); // We wait the maximum update interval to ensure // The stop will not be overwritten - usleep(tunes.get_maximum_update_interval()); + px4_usleep(tunes.get_maximum_update_interval()); } else { usage(); diff --git a/src/templates/module/module.cpp b/src/templates/module/module.cpp index 2527708668..27423a75e1 100644 --- a/src/templates/module/module.cpp +++ b/src/templates/module/module.cpp @@ -190,7 +190,7 @@ void Module::run() } else if (pret < 0) { // this is undesirable but not much we can do PX4_ERR("poll error %d, %d", pret, errno); - usleep(50000); + px4_usleep(50000); continue; } else if (fds[0].revents & POLLIN) { -- GitLab