mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 15:25:36 +03:00
Merge pull request #3614 from DanNixon/osd_ahi_config
Allow configuration of the AHI limits
This commit is contained in:
commit
fa4927c312
3 changed files with 21 additions and 9 deletions
|
@ -638,6 +638,9 @@ const clivalue_t valueTable[] = {
|
||||||
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
|
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
|
||||||
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
|
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
|
||||||
|
|
||||||
|
{ "osd_ah_max_pit", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 90 }, PG_OSD_CONFIG, offsetof(osdConfig_t, ahMaxPitch) },
|
||||||
|
{ "osd_ah_max_rol", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 90 }, PG_OSD_CONFIG, offsetof(osdConfig_t, ahMaxRoll) },
|
||||||
|
|
||||||
{ "osd_tim1", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, (uint16_t)0xFFFF }, PG_OSD_CONFIG, offsetof(osdConfig_t, timers[OSD_TIMER_1]) },
|
{ "osd_tim1", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, (uint16_t)0xFFFF }, PG_OSD_CONFIG, offsetof(osdConfig_t, timers[OSD_TIMER_1]) },
|
||||||
{ "osd_tim2", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, (uint16_t)0xFFFF }, PG_OSD_CONFIG, offsetof(osdConfig_t, timers[OSD_TIMER_2]) },
|
{ "osd_tim2", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, (uint16_t)0xFFFF }, PG_OSD_CONFIG, offsetof(osdConfig_t, timers[OSD_TIMER_2]) },
|
||||||
|
|
||||||
|
|
|
@ -134,8 +134,8 @@ static uint8_t armState;
|
||||||
|
|
||||||
static displayPort_t *osdDisplayPort;
|
static displayPort_t *osdDisplayPort;
|
||||||
|
|
||||||
#define AH_MAX_PITCH 200 // Specify maximum AHI pitch value displayed. Default 200 = 20.0 degrees
|
#define AH_SYMBOL_COUNT 9
|
||||||
#define AH_MAX_ROLL 400 // Specify maximum AHI roll value displayed. Default 400 = 40.0 degrees
|
|
||||||
#define AH_SIDEBAR_WIDTH_POS 7
|
#define AH_SIDEBAR_WIDTH_POS 7
|
||||||
#define AH_SIDEBAR_HEIGHT_POS 3
|
#define AH_SIDEBAR_HEIGHT_POS 3
|
||||||
|
|
||||||
|
@ -499,22 +499,25 @@ static void osdDrawSingleElement(uint8_t item)
|
||||||
elemPosX = 14;
|
elemPosX = 14;
|
||||||
elemPosY = 6 - 4; // Top center of the AH area
|
elemPosY = 6 - 4; // Top center of the AH area
|
||||||
|
|
||||||
const int rollAngle = constrain(attitude.values.roll, -AH_MAX_ROLL, AH_MAX_ROLL);
|
// Get pitch and roll limits in tenths of degrees
|
||||||
int pitchAngle = constrain(attitude.values.pitch, -AH_MAX_PITCH, AH_MAX_PITCH);
|
const int maxPitch = osdConfig()->ahMaxPitch * 10;
|
||||||
|
const int maxRoll = osdConfig()->ahMaxRoll * 10;
|
||||||
|
|
||||||
|
const int rollAngle = constrain(attitude.values.roll, -maxRoll, maxRoll);
|
||||||
|
int pitchAngle = constrain(attitude.values.pitch, -maxPitch, maxPitch);
|
||||||
|
|
||||||
if (displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL) {
|
if (displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL) {
|
||||||
++elemPosY;
|
++elemPosY;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Convert pitchAngle to y compensation value
|
// Convert pitchAngle to y compensation value
|
||||||
pitchAngle = (pitchAngle / 8) - 41; // 41 = 4 * 9 + 5
|
// (maxPitch / 25) divisor matches previous settings of fixed divisor of 8 and fixed max AHI pitch angle of 20.0 degrees
|
||||||
|
pitchAngle = ((pitchAngle * 25) / maxPitch) - 41; // 41 = 4 * AH_SYMBOL_COUNT + 5
|
||||||
|
|
||||||
for (int x = -4; x <= 4; x++) {
|
for (int x = -4; x <= 4; x++) {
|
||||||
int y = (-rollAngle * x) / 64;
|
const int y = ((-rollAngle * x) / 64) - pitchAngle;
|
||||||
y -= pitchAngle;
|
|
||||||
// y += 41; // == 4 * 9 + 5
|
|
||||||
if (y >= 0 && y <= 81) {
|
if (y >= 0 && y <= 81) {
|
||||||
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + (y / 9), (SYM_AH_BAR9_0 + (y % 9)));
|
displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + (y / AH_SYMBOL_COUNT), (SYM_AH_BAR9_0 + (y % AH_SYMBOL_COUNT)));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -824,6 +827,9 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
|
||||||
osdConfig->rssi_alarm = 20;
|
osdConfig->rssi_alarm = 20;
|
||||||
osdConfig->cap_alarm = 2200;
|
osdConfig->cap_alarm = 2200;
|
||||||
osdConfig->alt_alarm = 100; // meters or feet depend on configuration
|
osdConfig->alt_alarm = 100; // meters or feet depend on configuration
|
||||||
|
|
||||||
|
osdConfig->ahMaxPitch = 20; // 20 degrees
|
||||||
|
osdConfig->ahMaxRoll = 40; // 40 degrees
|
||||||
}
|
}
|
||||||
|
|
||||||
static void osdDrawLogo(int x, int y)
|
static void osdDrawLogo(int x, int y)
|
||||||
|
|
|
@ -138,6 +138,9 @@ typedef struct osdConfig_s {
|
||||||
osd_unit_e units;
|
osd_unit_e units;
|
||||||
|
|
||||||
uint16_t timers[OSD_TIMER_COUNT];
|
uint16_t timers[OSD_TIMER_COUNT];
|
||||||
|
|
||||||
|
uint8_t ahMaxPitch;
|
||||||
|
uint8_t ahMaxRoll;
|
||||||
} osdConfig_t;
|
} osdConfig_t;
|
||||||
|
|
||||||
extern uint32_t resumeRefreshAt;
|
extern uint32_t resumeRefreshAt;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue