HAL_PX4: disable checks for in_timerprocess

these are not valid in this form for the way the timer thread works on
PX4.
This commit is contained in:
Andrew Tridgell 2013-10-11 16:01:42 +11:00
parent 25d3e5b7e9
commit 63bee0b2d8
2 changed files with 6 additions and 0 deletions

View File

@ -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

View File

@ -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();