mirror of https://github.com/ArduPilot/ardupilot
AP_OSD: load font on startup
this reduces memory fragmemtation and maximises available memory during update
This commit is contained in:
parent
6347de2b89
commit
7454c9f8c5
|
@ -148,7 +148,10 @@ bool AP_OSD_MAX7456::init()
|
|||
hal.scheduler->delay(1);
|
||||
_dev->read_registers(MAX7456ADD_VM0|MAX7456ADD_READ, &status, 1);
|
||||
_dev->get_semaphore()->give();
|
||||
return status == 0;
|
||||
if (status != 0) {
|
||||
return false;
|
||||
}
|
||||
return update_font();
|
||||
}
|
||||
|
||||
bool AP_OSD_MAX7456::update_font()
|
||||
|
@ -342,10 +345,6 @@ void AP_OSD_MAX7456::reinit()
|
|||
|
||||
void AP_OSD_MAX7456::flush()
|
||||
{
|
||||
if (!font_updated) {
|
||||
update_font();
|
||||
font_updated = true;
|
||||
}
|
||||
check_reinit();
|
||||
transfer_frame();
|
||||
}
|
||||
|
|
|
@ -59,7 +59,6 @@ private:
|
|||
|
||||
uint8_t video_signal_reg;
|
||||
bool initialized;
|
||||
bool font_updated;
|
||||
|
||||
static const uint8_t video_lines_ntsc = 13;
|
||||
static const uint8_t video_lines_pal = 16;
|
||||
|
|
Loading…
Reference in New Issue