mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_OSD:add Aviation style AH option
This commit is contained in:
parent
2365f5ca1a
commit
63136e9060
@ -85,7 +85,7 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||||||
// @Param: _OPTIONS
|
// @Param: _OPTIONS
|
||||||
// @DisplayName: OSD Options
|
// @DisplayName: OSD Options
|
||||||
// @Description: This sets options that change the display
|
// @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
|
// @User: Standard
|
||||||
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),
|
AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),
|
||||||
|
|
||||||
|
@ -551,6 +551,7 @@ public:
|
|||||||
OPTION_IMPERIAL_MILES = 1U<<3,
|
OPTION_IMPERIAL_MILES = 1U<<3,
|
||||||
OPTION_DISABLE_CROSSHAIR = 1U<<4,
|
OPTION_DISABLE_CROSSHAIR = 1U<<4,
|
||||||
OPTION_BF_ARROWS = 1U<<5,
|
OPTION_BF_ARROWS = 1U<<5,
|
||||||
|
OPTION_AVIATION_AH = 1U<<6,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum {
|
enum {
|
||||||
|
@ -1573,10 +1573,18 @@ void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
|
|||||||
WITH_SEMAPHORE(ahrs.get_semaphore());
|
WITH_SEMAPHORE(ahrs.get_semaphore());
|
||||||
float roll;
|
float roll;
|
||||||
float pitch;
|
float pitch;
|
||||||
|
bool inverted = false;
|
||||||
AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch);
|
AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch);
|
||||||
pitch *= -1;
|
pitch *= -1;
|
||||||
|
// Are we inverted? then flash horizon line
|
||||||
//inverted roll AH
|
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)) {
|
if (check_option(AP_OSD::OPTION_INVERTED_AH_ROLL)) {
|
||||||
roll = -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
|
//chars in font in reversed order
|
||||||
c = SYMBOL(SYM_AH_H_START) + ((SYMBOL(SYM_AH_H_COUNT) - 1) - c);
|
c = SYMBOL(SYM_AH_H_START) + ((SYMBOL(SYM_AH_H_COUNT) - 1) - c);
|
||||||
if (dy >= -4 && dy <= 4) {
|
if (dy >= -4 && dy <= 4) {
|
||||||
backend->write(x + dx, y - dy, false, "%c", c);
|
backend->write(x + dx, y - dy, inverted, "%c", c);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} 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);
|
char c = (fx - dx) * SYMBOL(SYM_AH_V_COUNT);
|
||||||
c = SYMBOL(SYM_AH_V_START) + c;
|
c = SYMBOL(SYM_AH_V_START) + c;
|
||||||
if (dx >= -4 && dx <=4) {
|
if (dx >= -4 && dx <=4) {
|
||||||
backend->write(x + dx, y - dy, false, "%c", c);
|
backend->write(x + dx, y - dy, inverted, "%c", c);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user