AP_OSD: fixes from review comments
This commit is contained in:
parent
06fdc50169
commit
76fd0962e7
@ -31,11 +31,12 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||||||
// @Description: OSD type
|
// @Description: OSD type
|
||||||
// @Values: 0:None,1:MAX7456
|
// @Values: 0:None,1:MAX7456
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
|
// @RebootRequired: True
|
||||||
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_OSD, osd_type, 0, AP_PARAM_FLAG_ENABLE),
|
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_OSD, osd_type, 0, AP_PARAM_FLAG_ENABLE),
|
||||||
|
|
||||||
// @Param: _UPDATE_FONT
|
// @Param: _UPDATE_FONT
|
||||||
// @DisplayName: Update font
|
// @DisplayName: Update font
|
||||||
// @Description: Undate font inside osd chip
|
// @Description: Update font inside osd chip
|
||||||
// @Values: 0:Do not update,1:Update
|
// @Values: 0:Do not update,1:Update
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_UPDATE_FONT", 2, AP_OSD, update_font, 1),
|
AP_GROUPINFO("_UPDATE_FONT", 2, AP_OSD, update_font, 1),
|
||||||
@ -48,11 +49,11 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||||||
// @Path: AP_OSD_Screen.cpp
|
// @Path: AP_OSD_Screen.cpp
|
||||||
AP_SUBGROUPINFO(screen[1], "2_", 4, AP_OSD, AP_OSD_Screen),
|
AP_SUBGROUPINFO(screen[1], "2_", 4, AP_OSD, AP_OSD_Screen),
|
||||||
|
|
||||||
// @Group: 2_
|
// @Group: 3_
|
||||||
// @Path: AP_OSD_Screen.cpp
|
// @Path: AP_OSD_Screen.cpp
|
||||||
AP_SUBGROUPINFO(screen[2], "3_", 5, AP_OSD, AP_OSD_Screen),
|
AP_SUBGROUPINFO(screen[2], "3_", 5, AP_OSD, AP_OSD_Screen),
|
||||||
|
|
||||||
// @Group: 2_
|
// @Group: 4_
|
||||||
// @Path: AP_OSD_Screen.cpp
|
// @Path: AP_OSD_Screen.cpp
|
||||||
AP_SUBGROUPINFO(screen[3], "4_", 6, AP_OSD, AP_OSD_Screen),
|
AP_SUBGROUPINFO(screen[3], "4_", 6, AP_OSD, AP_OSD_Screen),
|
||||||
|
|
||||||
@ -72,6 +73,7 @@ void AP_OSD::init()
|
|||||||
{
|
{
|
||||||
switch ((enum osd_types)osd_type.get()) {
|
switch ((enum osd_types)osd_type.get()) {
|
||||||
case OSD_NONE:
|
case OSD_NONE:
|
||||||
|
default:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case OSD_MAX7456:
|
case OSD_MAX7456:
|
||||||
@ -93,7 +95,7 @@ void AP_OSD::timer()
|
|||||||
{
|
{
|
||||||
uint32_t now = AP_HAL::millis();
|
uint32_t now = AP_HAL::millis();
|
||||||
|
|
||||||
if (now - last_update_ms > 100) {
|
if (now - last_update_ms >= 100) {
|
||||||
last_update_ms = now;
|
last_update_ms = now;
|
||||||
update_osd();
|
update_osd();
|
||||||
}
|
}
|
||||||
|
@ -25,8 +25,6 @@
|
|||||||
|
|
||||||
#include <utility>
|
#include <utility>
|
||||||
|
|
||||||
#define VIDEO_LINES_NTSC 13
|
|
||||||
#define VIDEO_LINES_PAL 16
|
|
||||||
#define VIDEO_COLUMNS 30
|
#define VIDEO_COLUMNS 30
|
||||||
#define NVM_RAM_SIZE 54
|
#define NVM_RAM_SIZE 54
|
||||||
|
|
||||||
@ -162,7 +160,7 @@ bool AP_OSD_MAX7456::update_font()
|
|||||||
for (uint16_t chr=0; chr < 256; chr++) {
|
for (uint16_t chr=0; chr < 256; chr++) {
|
||||||
uint8_t status;
|
uint8_t status;
|
||||||
const uint8_t* chr_font_data = font_data + chr*NVM_RAM_SIZE;
|
const uint8_t* chr_font_data = font_data + chr*NVM_RAM_SIZE;
|
||||||
int retry;
|
uint16_t retry;
|
||||||
buffer_offset = 0;
|
buffer_offset = 0;
|
||||||
buffer_add_cmd(MAX7456ADD_VM0, 0);
|
buffer_add_cmd(MAX7456ADD_VM0, 0);
|
||||||
buffer_add_cmd(MAX7456ADD_CMAH, chr);
|
buffer_add_cmd(MAX7456ADD_CMAH, chr);
|
||||||
|
Loading…
Reference in New Issue
Block a user