AP_OSD: Add sidebars for MAX7456

This commit is contained in:
Sebastian Quilter 2021-08-28 13:21:57 -07:00 committed by Andrew Tridgell
parent 51d9714dbb
commit 2379036e9a
6 changed files with 235 additions and 128 deletions

View File

@ -52,7 +52,7 @@ class AP_MSP;
#define PARAM_INDEX(key, idx, group) (uint32_t(uint32_t(key) << 23 | uint32_t(idx) << 18 | uint32_t(group)))
#define PARAM_TOKEN_INDEX(token) PARAM_INDEX(AP_Param::get_persistent_key(token.key), token.idx, token.group_element)
#define AP_OSD_NUM_SYMBOLS 79
#define AP_OSD_NUM_SYMBOLS 91
/*
class to hold one setting
*/
@ -194,9 +194,9 @@ private:
#if HAL_PLUSCODE_ENABLE
AP_OSD_Setting pluscode{false, 0, 0};
#endif
AP_OSD_Setting sidebars{false, 4, 5};
// MSP OSD only
AP_OSD_Setting sidebars{false, 0, 0};
AP_OSD_Setting crosshair{false, 0, 0};
AP_OSD_Setting home_dist{true, 1, 1};
AP_OSD_Setting home_dir{true, 1, 1};
@ -223,6 +223,7 @@ private:
void draw_home(uint8_t x, uint8_t y);
void draw_throttle(uint8_t x, uint8_t y);
void draw_heading(uint8_t x, uint8_t y);
void draw_sidebars(uint8_t x, uint8_t y);
void draw_compass(uint8_t x, uint8_t y);
void draw_wind(uint8_t x, uint8_t y);
void draw_aspeed(uint8_t x, uint8_t y);

View File

@ -180,6 +180,19 @@ protected:
static const uint8_t SYM_RNGFD = 0xF7;
static const uint8_t SYM_LQ = 0xF8;
static const uint8_t SYM_SIDEBAR_R_ARROW = 0x09;
static const uint8_t SYM_SIDEBAR_L_ARROW = 0x0A;
static const uint8_t SYM_SIDEBAR_A = 0x13;
static const uint8_t SYM_SIDEBAR_B = 0x14;
static const uint8_t SYM_SIDEBAR_C = 0x15;
static const uint8_t SYM_SIDEBAR_D = 0xDD;
static const uint8_t SYM_SIDEBAR_E = 0xDB;
static const uint8_t SYM_SIDEBAR_F = 0xDC;
static const uint8_t SYM_SIDEBAR_G = 0xDA;
static const uint8_t SYM_SIDEBAR_H = 0xDE;
static const uint8_t SYM_SIDEBAR_I = 0x11;
static const uint8_t SYM_SIDEBAR_J = 0x12;
static constexpr uint8_t symbols[AP_OSD_NUM_SYMBOLS] {
SYM_M,
SYM_KM,
@ -260,5 +273,17 @@ protected:
SYM_FENCE_DISABLED,
SYM_RNGFD,
SYM_LQ,
SYM_SIDEBAR_R_ARROW,
SYM_SIDEBAR_L_ARROW,
SYM_SIDEBAR_A,
SYM_SIDEBAR_B,
SYM_SIDEBAR_C,
SYM_SIDEBAR_D,
SYM_SIDEBAR_E,
SYM_SIDEBAR_F,
SYM_SIDEBAR_G,
SYM_SIDEBAR_H,
SYM_SIDEBAR_I,
SYM_SIDEBAR_J,
};
};

View File

@ -716,23 +716,23 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// @Range: 0 15
AP_SUBGROUPINFO(clk, "CLK", 43, AP_OSD_Screen, AP_OSD_Setting),
#if HAL_MSP_ENABLED
// @Param: SIDEBARS_EN
// @DisplayName: SIDEBARS_EN
// @Description: Displays artificial horizon side bars (MSP OSD only)
// @Description: Displays artificial horizon side bars
// @Values: 0:Disabled,1:Enabled
// @Param: SIDEBARS_X
// @DisplayName: SIDEBARS_X
// @Description: Horizontal position on screen (MSP OSD only)
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: SIDEBARS_Y
// @DisplayName: SIDEBARS_Y
// @Description: Vertical position on screen (MSP OSD only)
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(sidebars, "SIDEBARS", 44, AP_OSD_Screen, AP_OSD_Setting),
#if HAL_MSP_ENABLED
// @Param: CRSSHAIR_EN
// @DisplayName: CRSSHAIR_EN
// @Description: Displays artificial horizon crosshair (MSP OSD only)
@ -1115,6 +1115,19 @@ uint8_t AP_OSD_AbstractScreen::symbols_lookup_table[AP_OSD_NUM_SYMBOLS];
#define SYM_RNGFD 77
#define SYM_LQ 78
#define SYM_SIDEBAR_R_ARROW 79
#define SYM_SIDEBAR_L_ARROW 80
#define SYM_SIDEBAR_A 81
#define SYM_SIDEBAR_B 82
#define SYM_SIDEBAR_C 83
#define SYM_SIDEBAR_D 84
#define SYM_SIDEBAR_E 85
#define SYM_SIDEBAR_F 86
#define SYM_SIDEBAR_G 87
#define SYM_SIDEBAR_H 88
#define SYM_SIDEBAR_I 89
#define SYM_SIDEBAR_J 90
#define SYMBOL(n) AP_OSD_AbstractScreen::symbols_lookup_table[n]
// constructor
@ -1386,6 +1399,7 @@ void AP_OSD_Screen::draw_batused(uint8_t x, uint8_t y)
//Thanks to night-ghost for the approach.
void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y)
{
x = 2; //messages get rendered across a whole row. User param x is ignored.
AP_Notify * notify = AP_Notify::get_singleton();
if (notify) {
int32_t visible_time = AP_HAL::millis() - notify->get_text_updated_millis();
@ -1429,6 +1443,9 @@ void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y)
//trim invisible part
buffer[end_position] = 0;
} else if (len < message_visible_width) {
//for short messages, start writing closer to the middle to center the text
x += (message_visible_width - len)/2;
}
backend->write(x, y, buffer + start_position);
@ -1572,6 +1589,69 @@ void AP_OSD_Screen::draw_throttle(uint8_t x, uint8_t y)
backend->write(x, y, false, "%3d%c", gcs().get_hud_throttle(), SYMBOL(SYM_PCNT));
}
void AP_OSD_Screen::draw_sidebars(uint8_t x, uint8_t y)
{
const int8_t total_sectors = 18;
static const uint8_t sidebar_sectors[total_sectors] = {
SYM_SIDEBAR_A,
SYM_SIDEBAR_B,
SYM_SIDEBAR_C,
SYM_SIDEBAR_D,
SYM_SIDEBAR_E,
SYM_SIDEBAR_F,
SYM_SIDEBAR_G,
SYM_SIDEBAR_E,
SYM_SIDEBAR_F,
SYM_SIDEBAR_G,
SYM_SIDEBAR_E,
SYM_SIDEBAR_F,
SYM_SIDEBAR_G,
SYM_SIDEBAR_E,
SYM_SIDEBAR_F,
SYM_SIDEBAR_H,
SYM_SIDEBAR_I,
SYM_SIDEBAR_J,
};
// Get altitude and airspeed, scaled to appropriate units
float aspd = 0.0f;
float alt = 0.0f;
AP_AHRS &ahrs = AP::ahrs();
WITH_SEMAPHORE(ahrs.get_semaphore());
bool have_speed_estimate = ahrs.airspeed_estimate(aspd);
if (!have_speed_estimate) { aspd = 0.0f; }
ahrs.get_relative_position_D_home(alt);
float scaled_aspd = u_scale(SPEED, aspd);
float scaled_alt = u_scale(ALTITUDE, -alt);
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;
// 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) {
// 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 {
backend->write(x+4, y+i, false, "%c", SYMBOL(sidebar_sectors[aspd_symbol_index]));
}
aspd_symbol_index = (aspd_symbol_index + 12) % 18;
}
// 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) {
// 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));
} else {
backend->write(x+16, y+i, false, "%c", SYMBOL(sidebar_sectors[alt_symbol_index]));
}
alt_symbol_index = (alt_symbol_index + 12) % 18;
}
}
//Thanks to betaflight/inav for simple and clean compass visual design
void AP_OSD_Screen::draw_compass(uint8_t x, uint8_t y)
{
@ -2071,6 +2151,7 @@ void AP_OSD_Screen::draw(void)
//Note: draw order should be optimized.
//Big and less important items should be drawn first,
//so they will not overwrite more important ones.
DRAW_SETTING(sidebars);
DRAW_SETTING(message);
DRAW_SETTING(horizon);
DRAW_SETTING(compass);

View File

@ -579,116 +579,116 @@ MAX7456
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01011010
10100101
01010101
01010000
00010101
01010101
01010010
00000101
01010101
01010010
01010101
00000001
01010101
01010101
00100000
01010101
01010101
00101000
00010101
01010101
00101010
00000101
01010101
00101010
10000001
01010101
01010010
00101010
10100000
01010101
01010010
00101010
10101000
00010101
01010010
10101010
00010101
01010010
01010101
00101010
10101000
00010101
01010010
01010101
00101010
10100000
01010101
01010010
00101010
10000001
01010101
01010010
00101010
00000101
01010101
01010000
00101000
00010101
01010101
01011010
10100101
00100000
01010101
01010101
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01011010
10100101
01010101
01010100
00000101
01010101
01010000
10000101
01010101
01000010
10000101
01010101
00001010
10000101
01010100
00101010
10000101
01010100
10101010
10000101
01010100
00101010
10000101
01010101
00001010
10000101
01010101
01000010
10000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
10000101
01010101
01010101
01000000
01010101
01010101
00001000
01010101
01010100
00000101
00101000
01010101
01011010
10100101
01010000
10101000
01010101
01000010
10101000
01010101
00001010
10101000
01010101
00101010
10101000
01010101
00101010
10101000
01010101
00001010
10101000
01010101
01000010
10101000
01010101
01010000
10101000
01010101
01010100
00101000
01010101
01010101
00001000
01010101
01010101
01000000
01010101
01010101
01010000
01010101
01010101
01010101
@ -13952,8 +13952,10 @@ MAX7456
01010101
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -13971,12 +13973,16 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -13994,8 +14000,10 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
01010101
@ -14011,12 +14019,16 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -14034,12 +14046,16 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -14076,12 +14092,16 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -14099,12 +14119,16 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -14120,8 +14144,10 @@ MAX7456
01010101
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -14139,12 +14165,16 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -14162,7 +14192,11 @@ MAX7456
01010101
01010101
01010101
00000000
01010101
01010100
10101010
00010101
01010101
01010101
01010101
@ -14173,7 +14207,11 @@ MAX7456
01010101
01010101
01010101
01010100
10101010
00010101
01010101
00000000
01010101
01010101
01010101
@ -14191,12 +14229,16 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
@ -14214,52 +14256,10 @@ MAX7456
01010101
01010101
01010101
01000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00101000
01010101
01010101
01010101

Binary file not shown.

Before

Width:  |  Height:  |  Size: 12 KiB

After

Width:  |  Height:  |  Size: 39 KiB

Binary file not shown.