AP_OSD:add Aviation style AH option

This commit is contained in:
Henry Wurzburg 2023-09-10 10:00:51 -05:00 committed by Andrew Tridgell
parent 2365f5ca1a
commit 63136e9060
3 changed files with 14 additions and 5 deletions

View File

@ -85,7 +85,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @Param: _OPTIONS
// @DisplayName: OSD Options
// @Description: This sets options that change the display
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows
// @Bitmask: 0:UseDecimalPack, 1:InvertedWindArrow, 2:InvertedAHRoll, 3:Convert feet to miles at 5280ft instead of 10000ft, 4:DisableCrosshair, 5:TranslateArrows, 6:AviationStyleAH
// @User: Standard
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),

View File

@ -551,6 +551,7 @@ public:
OPTION_IMPERIAL_MILES = 1U<<3,
OPTION_DISABLE_CROSSHAIR = 1U<<4,
OPTION_BF_ARROWS = 1U<<5,
OPTION_AVIATION_AH = 1U<<6,
};
enum {

View File

@ -1573,10 +1573,18 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
WITH_SEMAPHORE(ahrs.get_semaphore());
float roll;
float pitch;
bool inverted = false;
AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch);
pitch *= -1;
//inverted roll AH
// Are we inverted? then flash horizon line
if (abs(roll) >= radians(90)) {
inverted = true;
}
// Aviation style AH instead of Betaflight FPV style
if (inverted && check_option(AP_OSD::OPTION_AVIATION_AH)) {
pitch = -pitch;
}
//inverted roll AH (Russian HUD emulation)
if (check_option(AP_OSD::OPTION_INVERTED_AH_ROLL)) {
roll = -roll;
}
@ -1595,7 +1603,7 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
//chars in font in reversed order
c = SYMBOL(SYM_AH_H_START) + ((SYMBOL(SYM_AH_H_COUNT) - 1) - c);
if (dy >= -4 && dy <= 4) {
backend->write(x + dx, y - dy, false, "%c", c);
backend->write(x + dx, y - dy, inverted, "%c", c);
}
}
} else {
@ -1605,7 +1613,7 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
char c = (fx - dx) * SYMBOL(SYM_AH_V_COUNT);
c = SYMBOL(SYM_AH_V_START) + c;
if (dx >= -4 && dx <=4) {
backend->write(x + dx, y - dy, false, "%c", c);
backend->write(x + dx, y - dy, inverted, "%c", c);
}
}
}