AP_OSD: allow to fine tune osd position

This commit is contained in:
Alexander Malishev 2018-07-06 00:31:16 +04:00 committed by Andrew Tridgell
parent dc454881df
commit 7873aff0b8
3 changed files with 28 additions and 5 deletions

View File

@ -84,6 +84,20 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @RebootRequired: True
AP_GROUPINFO("_FONT", 9, AP_OSD, font_num, 0),
// @Param: _V_OFFSET
// @DisplayName: OSD vertical offset
// @Description: Sets vertical offset of the osd inside image
// @Range: 0 31
// @User: Standard
AP_GROUPINFO("_V_OFFSET", 10, AP_OSD, v_offset, 16),
// @Param: _H_OFFSET
// @DisplayName: OSD horizontal offset
// @Description: Sets horizontal offset of the osd inside image
// @Range: 0 63
// @User: Standard
AP_GROUPINFO("_H_OFFSET", 11, AP_OSD, h_offset, 32),
AP_GROUPEND
};

View File

@ -163,6 +163,9 @@ public:
AP_Int8 sw_method;
AP_Int8 font_num;
AP_Int8 v_offset;
AP_Int8 h_offset;
enum {
OPTION_DECIMAL_PACK = 1U<<0,
};

View File

@ -337,6 +337,12 @@ void AP_OSD_MAX7456::reinit()
_dev->write_register(MAX7456ADD_VM1, BLINK_DUTY_CYCLE_50_50 | BLINK_TIME_3 | BACKGROUND_BRIGHTNESS_28);
_dev->write_register(MAX7456ADD_DMM, DMM_CLEAR_DISPLAY);
//write osd position
int8_t hos = constrain_int16(_osd.h_offset, 0, 63);
int8_t vos = constrain_int16(_osd.v_offset, 0, 31);
_dev->write_register(MAX7456ADD_HOS, hos);
_dev->write_register(MAX7456ADD_VOS, vos);
// force redrawing all screen
memset(shadow_frame, 0xFF, sizeof(shadow_frame));
memset(shadow_attr, 0xFF, sizeof(shadow_attr));