mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: Fixed UART thread ownership for the MSP DisplayPort OSD Backend
This commit is contained in:
parent
0654ed74e3
commit
ca588b2eed
|
@ -320,6 +320,9 @@ void AP_OSD::init()
|
|||
#if OSD_ENABLED
|
||||
void AP_OSD::osd_thread()
|
||||
{
|
||||
// initialize thread specific code once
|
||||
backend->osd_thread_run_once();
|
||||
|
||||
while (true) {
|
||||
hal.scheduler->delay(100);
|
||||
update_osd();
|
||||
|
|
|
@ -56,6 +56,9 @@ public:
|
|||
// copy the backend specific symbol set to the OSD lookup table
|
||||
virtual void init_symbol_set(uint8_t *symbols, const uint8_t size);
|
||||
|
||||
// called by the OSD thread once
|
||||
virtual void osd_thread_run_once() { return; }
|
||||
|
||||
AP_OSD * get_osd()
|
||||
{
|
||||
return &_osd;
|
||||
|
|
|
@ -50,6 +50,14 @@ bool AP_OSD_MSP_DisplayPort::init(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
// called by the OSD thread once
|
||||
void AP_OSD_MSP_DisplayPort::osd_thread_run_once()
|
||||
{
|
||||
if (_displayport != nullptr) {
|
||||
_displayport->init_uart();
|
||||
}
|
||||
}
|
||||
|
||||
void AP_OSD_MSP_DisplayPort::clear(void)
|
||||
{
|
||||
// clear remote MSP screen
|
||||
|
|
|
@ -24,6 +24,10 @@ public:
|
|||
// copy the backend specific symbol set to the OSD lookup table
|
||||
void init_symbol_set(uint8_t *lookup_table, const uint8_t size) override;
|
||||
|
||||
// called by the OSD thread once
|
||||
// used to initialize the uart in the correct thread
|
||||
void osd_thread_run_once() override;
|
||||
|
||||
|
||||
protected:
|
||||
uint8_t format_string_for_osd(char* dst, uint8_t size, bool decimal_packed, const char *fmt, va_list ap) override;
|
||||
|
|
Loading…
Reference in New Issue