diff --git a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp index d697ec5da5..071c087c55 100644 --- a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp +++ b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp @@ -168,12 +168,14 @@ static int main_loop(int argc, char **argv) perf_end(perf_loop); +#if 0 if (hal.scheduler->in_timerprocess()) { // we are running when a timer process is running! This is // a scheduling error, and breaks the assumptions made in // our locking system ::printf("ERROR: timer processing running in loop()\n"); } +#endif /* give up 500 microseconds of time, to ensure drivers get a diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index e70df95adb..e6c297be3a 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -84,10 +84,12 @@ uint32_t PX4Scheduler::millis() void PX4Scheduler::delay_microseconds(uint16_t usec) { +#if 0 if (_in_timer_proc) { ::printf("ERROR: delay_microseconds() from timer process\n"); return; } +#endif perf_begin(_perf_delay); uint32_t start = micros(); uint32_t dt; @@ -99,10 +101,12 @@ void PX4Scheduler::delay_microseconds(uint16_t usec) void PX4Scheduler::delay(uint16_t ms) { +#if 0 if (_in_timer_proc) { ::printf("ERROR: delay() from timer process\n"); return; } +#endif perf_begin(_perf_delay); uint64_t start = hrt_absolute_time();