diff --git a/src/drivers/pwm_out_sim/PWMSim.cpp b/src/drivers/pwm_out_sim/PWMSim.cpp
index 83cb1f91e0753c7457b81fcb69b7220e91271e5e..d92d4254d003e4118f5594aa854f6148ee447895 100644
--- a/src/drivers/pwm_out_sim/PWMSim.cpp
+++ b/src/drivers/pwm_out_sim/PWMSim.cpp
@@ -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;
diff --git a/src/examples/hello/hello_example.cpp b/src/examples/hello/hello_example.cpp
index 6f7948a6bd3ad73b647e5bc0baa568c35833733b..5a3ebc60af28d07ca2db207b047c0c5044f0622b 100644
--- a/src/examples/hello/hello_example.cpp
+++ b/src/examples/hello/hello_example.cpp
@@ -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;
diff --git a/src/include/visibility.h b/src/include/visibility.h
index ff2c0db93ffe18f8dd2e7a963319a41703482ed0..3c74ce7832787bd4ed479a2ca4ffa2de2558d0ad 100644
--- a/src/include/visibility.h
+++ b/src/include/visibility.h
@@ -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 */
diff --git a/src/lib/cdev/test/cdevtest_example.cpp b/src/lib/cdev/test/cdevtest_example.cpp
index 7b8374ee1fa0dd82e5dda78bc784360bf41b7f37..1be2114a0a64d15039f558aa4618a35524445a22 100644
--- a/src/lib/cdev/test/cdevtest_example.cpp
+++ b/src/lib/cdev/test/cdevtest_example.cpp
@@ -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;
 }
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 29302ed7d89737af44d183c5db6f2bb06fdd55f5..2059afddb588f6be18e8ce0715500b2718f422b8 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -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();
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index 8929921b08dc3b73954392e97cb2cb5a2670fcce..5788dcda45c1efd93710574a3c570c5e9c53ea5f 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -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;
 
diff --git a/src/modules/commander/rc_check.cpp b/src/modules/commander/rc_check.cpp
index 582e73503bfe97933786d7ef28d3ee1050700ede..8d0c22527499b8170d1aada78e96a795f51453c0 100644
--- a/src/modules/commander/rc_check.cpp
+++ b/src/modules/commander/rc_check.cpp
@@ -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.",
diff --git a/src/platforms/apps.cpp.in b/src/platforms/apps.cpp.in
index f768845d99b13565f7c46859718f5fe0e3b98bd6..9f32d1505c0d433e7309f0e66f9c62baf6950a87 100644
--- a/src/platforms/apps.cpp.in
+++ b/src/platforms/apps.cpp.in
@@ -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;
 	}
 
diff --git a/src/platforms/px4_time.h b/src/platforms/px4_time.h
index ef22d7db6c82b9b15c8d1c4be79b84f9382851c2..80bfe34a76d8b1f82584b0c15b11fc693558b7dd 100644
--- a/src/platforms/px4_time.h
+++ b/src/platforms/px4_time.h
@@ -35,5 +35,6 @@ __END_DECLS
 #define px4_clock_settime clock_settime
 
 #define px4_usleep system_usleep
+#define px4_sleep system_sleep
 
 #endif
diff --git a/src/systemcmds/pwm/pwm.cpp b/src/systemcmds/pwm/pwm.cpp
index e01e0ca3891ea83006a8544fbd745150c500a570..50b9fa3a6cb9176bc445a08f8199c1990424022c 100644
--- a/src/systemcmds/pwm/pwm.cpp
+++ b/src/systemcmds/pwm/pwm.cpp
@@ -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");
diff --git a/src/systemcmds/tests/hrt_test/hrt_test.cpp b/src/systemcmds/tests/hrt_test/hrt_test.cpp
index 00fd2e99523cb4d564318c8b27aebef57616d99e..2b087bcc68c048a8f24f888fba19d9e6d34ad184 100644
--- a/src/systemcmds/tests/hrt_test/hrt_test.cpp
+++ b/src/systemcmds/tests/hrt_test/hrt_test.cpp
@@ -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));
diff --git a/src/systemcmds/tests/test_uart_console.c b/src/systemcmds/tests/test_uart_console.c
index 2c6adc7947327b0a33dcd592a444689019a4c982..d07e280270b715dd59a08ca0b392053d526ea36f 100644
--- a/src/systemcmds/tests/test_uart_console.c
+++ b/src/systemcmds/tests/test_uart_console.c
@@ -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();
diff --git a/src/systemcmds/top/top.c b/src/systemcmds/top/top.c
index b5cebc29d8aadd23733934d95aefd1080a309789..2ba775d47ddd0e701abe7f170e3cc14a6eb97771 100644
--- a/src/systemcmds/top/top.c
+++ b/src/systemcmds/top/top.c
@@ -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 {