Skip to content

Commit

Permalink
AP_OSD: Add configurable sidebar horizontal and vertical size extensions
Browse files Browse the repository at this point in the history
  • Loading branch information
rmaia3d committed Mar 26, 2024
1 parent ac271cf commit ed2dc0a
Show file tree
Hide file tree
Showing 3 changed files with 31 additions and 6 deletions.
16 changes: 16 additions & 0 deletions libraries/AP_OSD/AP_OSD.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,6 +214,22 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @User: Standard
AP_GROUPINFO("_W_ACRVOLT", 31, AP_OSD, warn_avgcellrestvolt, 3.6f),

#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", 36, 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", 37, AP_OSD, sidebar_v_ext, 0),
#endif // HAL_OSD_SIDEBAR_ENABLE

#endif //osd enabled
#if OSD_PARAM_ENABLED
// @Group: 5_
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_OSD/AP_OSD.h
Original file line number Diff line number Diff line change
Expand Up @@ -557,6 +557,11 @@ class AP_OSD
AP_Int8 failsafe_scr;
AP_Int32 button_delay_ms;

#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,
Expand Down
16 changes: 10 additions & 6 deletions libraries/AP_OSD/AP_OSD_Screen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1755,10 +1755,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 {
Expand All @@ -1770,12 +1774,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;
}
Expand Down

0 comments on commit ed2dc0a

Please sign in to comment.