AP_OSD: use thread_create API

this prevents a freeze in the FAT filesystem from affecting the OSD
This commit is contained in:
Andrew Tridgell 2018-07-07 09:30:53 +10:00
parent 9918ae3209
commit b98d941526
2 changed files with 8 additions and 8 deletions

View File

@ -109,7 +109,6 @@ void AP_OSD::init()
break;
}
hal.console->printf("Started MAX7456 OSD\n");
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_OSD::timer, void));
break;
}
@ -120,19 +119,20 @@ void AP_OSD::init()
break;
}
hal.console->printf("Started SITL OSD\n");
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_OSD::timer, void));
break;
}
#endif
}
if (backend != nullptr) {
// create thread as higher priority than IO
hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_OSD::osd_thread, void), "OSD", 512, AP_HAL::Scheduler::PRIORITY_IO, 1);
}
}
void AP_OSD::timer()
void AP_OSD::osd_thread()
{
uint32_t now = AP_HAL::millis();
if (now - last_update_ms >= 100) {
last_update_ms = now;
while (true) {
hal.scheduler->delay(100);
update_osd();
}
}

View File

@ -171,7 +171,7 @@ public:
AP_OSD_Screen screen[AP_OSD_NUM_SCREENS];
private:
void timer();
void osd_thread();
void update_osd();
void update_current_screen();
void next_screen();