diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index 3f1a7b8a49..23d3dd8e56 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -230,6 +230,22 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = { AP_GROUPINFO("_W_SNR", 34, AP_OSD, warn_snr, 0), #endif +#if HAL_OSD_SIDEBAR_ENABLE + // @Param: _SB_H_OFS + // @DisplayName: Sidebar horizontal offset + // @Description: Extends the spacing between the sidebar elements by this amount of columns. Positive values increases the width to the right of the screen. + // @Range: 0 20 + // @User: Standard + AP_GROUPINFO("_SB_H_OFS", 35, AP_OSD, sidebar_h_offset, 0), + + // @Param: _SB_V_EXT + // @DisplayName: Sidebar vertical extension + // @Description: Increase of vertical length of the sidebar itens by this amount of lines. Applied equally both above and below the default setting. + // @Range: 0 10 + // @User: Standard + AP_GROUPINFO("_SB_V_EXT", 36, AP_OSD, sidebar_v_ext, 0), +#endif // HAL_OSD_SIDEBAR_ENABLE + #endif //osd enabled #if OSD_PARAM_ENABLED // @Group: 5_ diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h index b57526b45b..4a09e6e1c5 100644 --- a/libraries/AP_OSD/AP_OSD.h +++ b/libraries/AP_OSD/AP_OSD.h @@ -591,6 +591,11 @@ public: AP_Int8 warn_snr; #endif +#if HAL_OSD_SIDEBAR_ENABLE + AP_Int8 sidebar_h_offset; + AP_Int8 sidebar_v_ext; +#endif + enum { OPTION_DECIMAL_PACK = 1U<<0, OPTION_INVERTED_WIND = 1U<<1, diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 01ea15a25e..8074ad2b6d 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -1862,10 +1862,14 @@ void AP_OSD_Screen::draw_sidebars(uint8_t x, uint8_t y) static const int aspd_interval = 10; //units between large tick marks int alt_interval = (osd->units == AP_OSD::UNITS_AVIATION || osd->units == AP_OSD::UNITS_IMPERIAL) ? 20 : 10; + // Height values taking into account configurable vertical extension + const int bar_total_height = 7 + (osd->sidebar_v_ext * 2); + const int bar_middle = bar_total_height / 2; // Integer division + // render airspeed ladder int aspd_symbol_index = fmodf(scaled_aspd, aspd_interval) / aspd_interval * total_sectors; - for (int i = 0; i < 7; i++){ - if (i == 3) { + for (int i = 0; i < bar_total_height; i++){ + if (i == bar_middle) { // the middle section of the ladder with the currrent airspeed backend->write(x, y+i, false, "%3d%c%c", (int) scaled_aspd, u_icon(SPEED), SYMBOL(SYM_SIDEBAR_R_ARROW)); } else { @@ -1877,12 +1881,12 @@ void AP_OSD_Screen::draw_sidebars(uint8_t x, uint8_t y) // render the altitude ladder // similar formula to above, but accounts for negative altitudes int alt_symbol_index = fmodf(fmodf(scaled_alt, alt_interval) + alt_interval, alt_interval) / alt_interval * total_sectors; - for (int i = 0; i < 7; i++){ - if (i == 3) { + for (int i = 0; i < bar_total_height; i++){ + if (i == bar_middle) { // the middle section of the ladder with the currrent altitude - backend->write(x+16, y+i, false, "%c%d%c", SYMBOL(SYM_SIDEBAR_L_ARROW), (int) scaled_alt, u_icon(ALTITUDE)); + backend->write(x + 16 + osd->sidebar_h_offset, y+i, false, "%c%d%c", SYMBOL(SYM_SIDEBAR_L_ARROW), (int) scaled_alt, u_icon(ALTITUDE)); } else { - backend->write(x+16, y+i, false, "%c", SYMBOL(sidebar_sectors[alt_symbol_index])); + backend->write(x + 16 + osd->sidebar_h_offset, y+i, false, "%c", SYMBOL(sidebar_sectors[alt_symbol_index])); } alt_symbol_index = (alt_symbol_index + 12) % 18; }