HAL_PX4: split IO thread into separate IO and storage threads

this prevents a blocked microSD card from blocking IO to the FRAM,
causing parameter changes not to be sticky
This commit is contained in:
Andrew Tridgell 2015-03-04 20:07:11 +11:00
parent 58c92b0158
commit 086f878bdc
2 changed files with 32 additions and 4 deletions

View File

@ -33,6 +33,7 @@ extern bool _px4_thread_should_exit;
PX4Scheduler::PX4Scheduler() :
_perf_timers(perf_alloc(PC_ELAPSED, "APM_timers")),
_perf_io_timers(perf_alloc(PC_ELAPSED, "APM_IO_timers")),
_perf_storage_timer(perf_alloc(PC_ELAPSED, "APM_storage_timers")),
_perf_delay(perf_alloc(PC_ELAPSED, "APM_delay"))
{}
@ -72,6 +73,16 @@ void PX4Scheduler::init(void *unused)
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
pthread_create(&_io_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_io_thread, this);
// the storage thread runs at just above IO priority
pthread_attr_init(&thread_attr);
pthread_attr_setstacksize(&thread_attr, 1024);
param.sched_priority = APM_STORAGE_PRIORITY;
(void)pthread_attr_setschedparam(&thread_attr, &param);
pthread_attr_setschedpolicy(&thread_attr, SCHED_FIFO);
pthread_create(&_storage_thread_ctx, &thread_attr, (pthread_startroutine_t)&PX4::PX4Scheduler::_storage_thread, this);
}
uint64_t PX4Scheduler::micros64()
@ -339,9 +350,6 @@ void *PX4Scheduler::_io_thread(void)
while (!_px4_thread_should_exit) {
poll(NULL, 0, 1);
// process any pending storage writes
((PX4Storage *)hal.storage)->_timer_tick();
// run registered IO processes
perf_begin(_perf_io_timers);
_run_io();
@ -350,6 +358,22 @@ void *PX4Scheduler::_io_thread(void)
return NULL;
}
void *PX4Scheduler::_storage_thread(void)
{
while (!_hal_initialized) {
poll(NULL, 0, 1);
}
while (!_px4_thread_should_exit) {
poll(NULL, 0, 10);
// process any pending storage writes
perf_begin(_perf_storage_timer);
((PX4Storage *)hal.storage)->_timer_tick();
perf_end(_perf_storage_timer);
}
return NULL;
}
void PX4Scheduler::panic(const prog_char_t *errormsg)
{
write(1, errormsg, strlen(errormsg));

View File

@ -16,7 +16,8 @@
#define APM_MAIN_PRIORITY 180
#define APM_TIMER_PRIORITY 181
#define APM_UART_PRIORITY 60
#define APM_IO_PRIORITY 59
#define APM_STORAGE_PRIORITY 59
#define APM_IO_PRIORITY 58
#define APM_OVERTIME_PRIORITY 10
#define APM_STARTUP_PRIORITY 10
@ -88,10 +89,12 @@ private:
pid_t _main_task_pid;
pthread_t _timer_thread_ctx;
pthread_t _io_thread_ctx;
pthread_t _storage_thread_ctx;
pthread_t _uart_thread_ctx;
void *_timer_thread(void);
void *_io_thread(void);
void *_storage_thread(void);
void *_uart_thread(void);
void _run_timers(bool called_from_timer_thread);
@ -101,6 +104,7 @@ private:
perf_counter_t _perf_timers;
perf_counter_t _perf_io_timers;
perf_counter_t _perf_storage_timer;
perf_counter_t _perf_delay;
};
#endif