|
|
|
@ -347,7 +347,6 @@ void AP_OSD_MAX7456::reinit()
@@ -347,7 +347,6 @@ void AP_OSD_MAX7456::reinit()
|
|
|
|
|
|
|
|
|
|
// force redrawing all screen
|
|
|
|
|
memset(shadow_frame, 0xFF, sizeof(shadow_frame)); |
|
|
|
|
memset(shadow_attr, 0xFF, sizeof(shadow_attr)); |
|
|
|
|
|
|
|
|
|
initialized = true; |
|
|
|
|
} |
|
|
|
@ -357,7 +356,7 @@ void AP_OSD_MAX7456::flush()
@@ -357,7 +356,7 @@ void AP_OSD_MAX7456::flush()
|
|
|
|
|
if (last_font != get_font_num()) { |
|
|
|
|
update_font(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// check for offset changes
|
|
|
|
|
if (last_v_offset != _osd.v_offset) { |
|
|
|
|
int8_t vos = constrain_int16(_osd.v_offset, 0, 31); |
|
|
|
@ -373,15 +372,15 @@ void AP_OSD_MAX7456::flush()
@@ -373,15 +372,15 @@ void AP_OSD_MAX7456::flush()
|
|
|
|
|
_dev->get_semaphore()->give(); |
|
|
|
|
last_h_offset = _osd.h_offset; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
check_reinit(); |
|
|
|
|
transfer_frame(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_OSD_MAX7456::transfer_frame() |
|
|
|
|
{ |
|
|
|
|
uint8_t last_attribute = 0xFF; |
|
|
|
|
uint16_t previous_pos = UINT16_MAX - 1; |
|
|
|
|
bool autoincrement = false; |
|
|
|
|
if (!initialized) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
@ -389,8 +388,7 @@ void AP_OSD_MAX7456::transfer_frame()
@@ -389,8 +388,7 @@ void AP_OSD_MAX7456::transfer_frame()
|
|
|
|
|
buffer_offset = 0; |
|
|
|
|
for (uint8_t y=0; y<video_lines; y++) { |
|
|
|
|
for (uint8_t x=0; x<video_columns; x++) { |
|
|
|
|
|
|
|
|
|
if (frame[y][x] == shadow_frame[y][x] && attr[y][x] == shadow_attr[y][x]) { |
|
|
|
|
if (!is_dirty(x, y)) { |
|
|
|
|
continue; |
|
|
|
|
} |
|
|
|
|
//ensure space for 1 char and escape sequence
|
|
|
|
@ -398,58 +396,67 @@ void AP_OSD_MAX7456::transfer_frame()
@@ -398,58 +396,67 @@ void AP_OSD_MAX7456::transfer_frame()
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|
shadow_frame[y][x] = frame[y][x]; |
|
|
|
|
shadow_attr[y][x] = attr[y][x]; |
|
|
|
|
uint8_t attribute = attr[y][x] & (DMM_BLINK | DMM_INVERT_PIXEL_COLOR); |
|
|
|
|
uint8_t chr = frame[y][x]; |
|
|
|
|
uint16_t pos = y * video_columns + x; |
|
|
|
|
bool attribute_changed = (attribute != last_attribute); |
|
|
|
|
bool position_changed = ((previous_pos + 1) != pos); |
|
|
|
|
|
|
|
|
|
if (position_changed) { |
|
|
|
|
if (position_changed && autoincrement) { |
|
|
|
|
//it is impossible to write to MAX7456ADD_DMAH/MAX7456ADD_DMAL in autoincrement mode
|
|
|
|
|
//so, exit autoincrement mode
|
|
|
|
|
if (buffer_offset != 0) { |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMDI, 0xFF); |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMM, 0); |
|
|
|
|
} |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMDI, 0xFF); |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMM, 0); |
|
|
|
|
autoincrement = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (!autoincrement) { |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMAH, pos >> 8); |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMAL, pos & 0xFF); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
//update character attributes and (re)enter autoincrement mode
|
|
|
|
|
if (position_changed || attribute_changed) { |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMM, attribute | DMM_AUTOINCREMENT); |
|
|
|
|
last_attribute = attribute; |
|
|
|
|
if (!autoincrement && is_dirty(x+1, y)) { |
|
|
|
|
//(re)enter autoincrement mode
|
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMM, DMM_AUTOINCREMENT); |
|
|
|
|
autoincrement = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMDI, chr); |
|
|
|
|
previous_pos = pos; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (buffer_offset > 0) { |
|
|
|
|
if (autoincrement) { |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMDI, 0xFF); |
|
|
|
|
buffer_add_cmd(MAX7456ADD_DMM, 0); |
|
|
|
|
autoincrement = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (buffer_offset > 0) { |
|
|
|
|
_dev->get_semaphore()->take_blocking(); |
|
|
|
|
_dev->transfer(buffer, buffer_offset, nullptr, 0); |
|
|
|
|
_dev->get_semaphore()->give(); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool AP_OSD_MAX7456::is_dirty(uint8_t x, uint8_t y) |
|
|
|
|
{ |
|
|
|
|
if (y>=video_lines || x>=video_columns) { |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
return frame[y][x] != shadow_frame[y][x]; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_OSD_MAX7456::clear() |
|
|
|
|
{ |
|
|
|
|
AP_OSD_Backend::clear(); |
|
|
|
|
memset(frame, ' ', sizeof(frame)); |
|
|
|
|
memset(attr, 0, sizeof(attr)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_OSD_MAX7456::write(uint8_t x, uint8_t y, const char* text, uint8_t char_attr) |
|
|
|
|
void AP_OSD_MAX7456::write(uint8_t x, uint8_t y, const char* text) |
|
|
|
|
{ |
|
|
|
|
if (y >= video_lines_pal || text == nullptr) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
while ((x < VIDEO_COLUMNS) && (*text != 0)) { |
|
|
|
|
frame[y][x] = *text; |
|
|
|
|
attr[y][x] = char_attr; |
|
|
|
|
++text; |
|
|
|
|
++x; |
|
|
|
|
} |
|
|
|
|