Replace sleep with px4_sleep

This is another step to isolate time from the system.
This commit is contained in:
Julian Oes 2018-10-04 10:19:06 +02:00
parent 3f695870a4
commit d70b0f1c8c
13 changed files with 20 additions and 15 deletions

View File

@ -31,6 +31,7 @@
*
****************************************************************************/
#include <px4_time.h>
#include "PWMSim.hpp"
#include <uORB/topics/multirotor_motor_limits.h>
@ -196,7 +197,7 @@ PWMSim::run()
/* this can happen during boot, but after the sleep its likely resolved */
if (_poll_fds_num == 0) {
sleep(1);
px4_sleep(1);
PX4_DEBUG("no valid fds");
continue;

View File

@ -40,7 +40,7 @@
*/
#include "hello_example.h"
#include <px4_time.h>
#include <unistd.h>
#include <stdio.h>
@ -53,7 +53,7 @@ int HelloExample::main()
int i = 0;
while (!appState.exitRequested() && i < 5) {
sleep(2);
px4_sleep(2);
printf(" Doing work...\n");
++i;

View File

@ -70,6 +70,8 @@
#include <unistd.h>
#define system_usleep usleep
#pragma GCC poison usleep
#define system_sleep sleep
#pragma GCC poison sleep
#ifdef __cplusplus
#include <cstdlib>
@ -90,6 +92,7 @@
// like uavcan and we don't need to fake time on the real system.
#include <unistd.h>
#define system_usleep usleep
#define system_sleep sleep
#pragma GCC poison getenv setenv putenv
#endif /* __PX4_NUTTX */

View File

@ -71,7 +71,7 @@ static int writer_main(int argc, char *argv[])
while (!g_exit) {
// Wait for 2 seconds
PX4_INFO("Writer: Sleeping for 2 sec");
ret = sleep(2);
ret = px4_sleep(2);
if (ret < 0) {
PX4_INFO("Writer: sleep failed %d %d", ret, errno);
@ -326,6 +326,6 @@ fail2:
g_exit = true;
px4_close(fd);
PX4_INFO("TEST: waiting for writer to stop");
sleep(3);
px4_sleep(3);
return ret;
}

View File

@ -840,7 +840,7 @@ int do_level_calibration(orb_advert_t *mavlink_log_pub)
while (hrt_elapsed_time(&start) < settle_time * 1000000) {
calibration_log_info(mavlink_log_pub, CAL_QGC_PROGRESS_MSG,
(int)(90 * hrt_elapsed_time(&start) / 1e6f / (float)settle_time));
sleep(settle_time / 10);
px4_sleep(settle_time / 10);
}
start = hrt_absolute_time();

View File

@ -60,7 +60,7 @@ static const char *sensor_name = "airspeed";
static void feedback_calibration_failed(orb_advert_t *mavlink_log_pub)
{
sleep(5);
px4_sleep(5);
calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name);
}
@ -284,7 +284,7 @@ normal_return:
px4_close(diff_pres_sub);
// This give a chance for the log messages to go out of the queue before someone else stomps on then
sleep(1);
px4_sleep(1);
return result;

View File

@ -223,7 +223,7 @@ int rc_calibration_check(orb_advert_t *mavlink_log_pub, bool report_fail, bool i
}
if (channels_failed) {
sleep(2);
px4_sleep(2);
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "%d config error%s for %d RC channel%s.",

View File

@ -112,7 +112,7 @@ int wait_for_topic(int argc, char *argv[])
while (orb_exists(&meta, 0) != 0 && (timeout && (elapsed < timeout)))
{
sleep(1);
px4_sleep(1);
elapsed += 1;
}

View File

@ -35,5 +35,6 @@ __END_DECLS
#define px4_clock_settime clock_settime
#define px4_usleep system_usleep
#define px4_sleep system_sleep
#endif

View File

@ -752,7 +752,7 @@ err_out_no_test:
fds.events = POLLIN;
PX4_WARN("Running 5 steps. WARNING! Motors will be live in 5 seconds\nPress any key to abort now.");
sleep(5);
px4_sleep(5);
if (::ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_ENTER_TEST_MODE) < 0) {
PX4_ERR("Failed to Enter pwm test mode");

View File

@ -76,7 +76,7 @@ int HRTTest::main()
PX4_INFO("Start time %llu\n", (unsigned long long)t);
t = hrt_absolute_time();
sleep(1);
px4_sleep(1);
elt = hrt_elapsed_time(&t);
PX4_INFO("Elapsed time %llu in 1 sec (sleep)\n", (unsigned long long)elt);
PX4_INFO("Start time %llu\n", (unsigned long long)t);
@ -86,7 +86,7 @@ int HRTTest::main()
PX4_INFO("HRT_CALL %d\n", hrt_called(&t1));
hrt_call_after(&t1, update_interval, timer_expired, (void *)nullptr);
sleep(2);
px4_sleep(2);
PX4_INFO("HRT_CALL - %d\n", hrt_called(&t1));
hrt_cancel(&t1);
PX4_INFO("HRT_CALL + %d\n", hrt_called(&t1));

View File

@ -94,7 +94,7 @@ int test_uart_console(int argc, char *argv[])
write(uart_usb, sample_uart_usb, sizeof(sample_uart_usb));
printf(".");
fflush(stdout);
sleep(1);
px4_sleep(1);
}
// uint64_t start_time = hrt_absolute_time();

View File

@ -80,7 +80,7 @@ top_main(int argc, char *argv[])
if (argc > 1) {
if (!strcmp(argv[1], "once")) {
print_load(curr_time, 1, &load);
sleep(1);
px4_sleep(1);
print_load(hrt_absolute_time(), 1, &load);
} else {