HAL_PX4: fixed a scheduler bug that affects UART IO

we need to detect if we are in a timer task using a PID, not a
flag. This is the same type of bug I fixed last week, but now fixed
properly.

The bug could well be the "USB bug" that Craig has been chasing
This commit is contained in:
Andrew Tridgell 2013-10-19 16:47:35 +11:00
parent 2593144b69
commit 1c091cbca5
3 changed files with 7 additions and 14 deletions

View File

@ -160,15 +160,6 @@ static int main_loop(int argc, char **argv)
perf_end(perf_loop); 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 give up 500 microseconds of time, to ensure drivers get a
chance to run. This relies on the accurate semaphore wait chance to run. This relies on the accurate semaphore wait

View File

@ -39,6 +39,8 @@ void PX4Scheduler::init(void *unused)
{ {
_sketch_start_time = hrt_absolute_time(); _sketch_start_time = hrt_absolute_time();
_main_task_pid = getpid();
// setup the timer thread - this will call tasks at 1kHz // setup the timer thread - this will call tasks at 1kHz
pthread_attr_t thread_attr; pthread_attr_t thread_attr;
struct sched_param param; struct sched_param param;
@ -113,12 +115,10 @@ void PX4Scheduler::delay_microseconds(uint16_t usec)
void PX4Scheduler::delay(uint16_t ms) void PX4Scheduler::delay(uint16_t ms)
{ {
#if 0 if (in_timerprocess()) {
if (_in_timer_proc) {
::printf("ERROR: delay() from timer process\n"); ::printf("ERROR: delay() from timer process\n");
return; return;
} }
#endif
perf_begin(_perf_delay); perf_begin(_perf_delay);
uint64_t start = hrt_absolute_time(); uint64_t start = hrt_absolute_time();
@ -305,8 +305,9 @@ void PX4Scheduler::panic(const prog_char_t *errormsg)
exit(1); exit(1);
} }
bool PX4Scheduler::in_timerprocess() { bool PX4Scheduler::in_timerprocess()
return _in_timer_proc; {
return getpid() != _main_task_pid;
} }
bool PX4Scheduler::system_initializing() { bool PX4Scheduler::system_initializing() {

View File

@ -63,6 +63,7 @@ private:
volatile bool _timer_event_missed; volatile bool _timer_event_missed;
pid_t _main_task_pid;
pthread_t _timer_thread_ctx; pthread_t _timer_thread_ctx;
pthread_t _io_thread_ctx; pthread_t _io_thread_ctx;
pthread_t _uart_thread_ctx; pthread_t _uart_thread_ctx;