1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

[OSD] Split OSD configuration into osdConfig_t and osdLayoutsConfig_t

osdLayoutsConfig_t stores the config for the layouts, with the visible
items and their positions. osdLayoutsConfig_t stores the rest.
This commit is contained in:
Alberto García Hierro 2020-06-09 23:58:52 +01:00
parent f50329b44d
commit e786889c86
7 changed files with 208 additions and 200 deletions

View file

@ -75,7 +75,7 @@ static long cmsx_osdElementOnChange(displayPort_t *displayPort, const void *ptr)
{ {
UNUSED(ptr); UNUSED(ptr);
uint16_t *pos = &osdConfigMutable()->item_pos[osdCurrentLayout][osdCurrentItem]; uint16_t *pos = &osdLayoutsConfigMutable()->item_pos[osdCurrentLayout][osdCurrentItem];
*pos = OSD_POS(osdCurrentElementColumn, osdCurrentElementRow); *pos = OSD_POS(osdCurrentElementColumn, osdCurrentElementRow);
if (osdCurrentElementVisible) { if (osdCurrentElementVisible) {
*pos |= OSD_VISIBLE_FLAG; *pos |= OSD_VISIBLE_FLAG;
@ -125,7 +125,7 @@ static CMS_Menu cmsx_menuOsdElementActions = {
static long osdElemActionsOnEnter(const OSD_Entry *from) static long osdElemActionsOnEnter(const OSD_Entry *from)
{ {
osdCurrentItem = from->itemId; osdCurrentItem = from->itemId;
uint16_t pos = osdConfig()->item_pos[osdCurrentLayout][osdCurrentItem]; uint16_t pos = osdLayoutsConfig()->item_pos[osdCurrentLayout][osdCurrentItem];
osdCurrentElementColumn = OSD_X(pos); osdCurrentElementColumn = OSD_X(pos);
osdCurrentElementRow = OSD_Y(pos); osdCurrentElementRow = OSD_Y(pos);
osdCurrentElementVisible = OSD_VISIBLE(pos) ? 1 : 0; osdCurrentElementVisible = OSD_VISIBLE(pos) ? 1 : 0;

View file

@ -112,7 +112,8 @@
#define PG_RPM_FILTER_CONFIG 1022 #define PG_RPM_FILTER_CONFIG 1022
#define PG_GLOBAL_VARIABLE_CONFIG 1023 #define PG_GLOBAL_VARIABLE_CONFIG 1023
#define PG_SMARTPORT_MASTER_CONFIG 1024 #define PG_SMARTPORT_MASTER_CONFIG 1024
#define PG_INAV_END 1024 #define PG_OSD_LAYOUTS_CONFIG 1025
#define PG_INAV_END 1025
// OSD configuration (subject to change) // OSD configuration (subject to change)
//#define PG_OSD_FONT_CONFIG 2047 //#define PG_OSD_FONT_CONFIG 2047

View file

@ -2221,7 +2221,7 @@ static void cliFlashRead(char *cmdline)
#endif #endif
#ifdef USE_OSD #ifdef USE_OSD
static void printOsdLayout(uint8_t dumpMask, const osdConfig_t *osdConfig, const osdConfig_t *osdConfigDefault, int layout, int item) static void printOsdLayout(uint8_t dumpMask, const osdLayoutsConfig_t *config, const osdLayoutsConfig_t *configDefault, int layout, int item)
{ {
// "<layout> <item> <col> <row> <visible>" // "<layout> <item> <col> <row> <visible>"
const char *format = "osd_layout %d %d %d %d %c"; const char *format = "osd_layout %d %d %d %d %c";
@ -2229,8 +2229,8 @@ static void printOsdLayout(uint8_t dumpMask, const osdConfig_t *osdConfig, const
if (layout >= 0 && layout != ii) { if (layout >= 0 && layout != ii) {
continue; continue;
} }
const uint16_t *layoutItems = osdConfig->item_pos[ii]; const uint16_t *layoutItems = config->item_pos[ii];
const uint16_t *defaultLayoutItems = osdConfigDefault->item_pos[ii]; const uint16_t *defaultLayoutItems = configDefault->item_pos[ii];
for (int jj = 0; jj < OSD_ITEM_COUNT; jj++) { for (int jj = 0; jj < OSD_ITEM_COUNT; jj++) {
if (item >= 0 && item != jj) { if (item >= 0 && item != jj) {
continue; continue;
@ -2322,15 +2322,15 @@ static void cliOsdLayout(char *cmdline)
// No args, or just layout or layout and item. If any of them not provided, // No args, or just layout or layout and item. If any of them not provided,
// it will be the -1 that we used during initialization, so printOsdLayout() // it will be the -1 that we used during initialization, so printOsdLayout()
// won't use them for filtering. // won't use them for filtering.
printOsdLayout(DUMP_MASTER, osdConfig(), osdConfig(), layout, item); printOsdLayout(DUMP_MASTER, osdLayoutsConfig(), osdLayoutsConfig(), layout, item);
break; break;
case 4: case 4:
// No visibility provided. Keep the previous one. // No visibility provided. Keep the previous one.
visible = OSD_VISIBLE(osdConfig()->item_pos[layout][item]); visible = OSD_VISIBLE(osdLayoutsConfig()->item_pos[layout][item]);
FALLTHROUGH; FALLTHROUGH;
case 5: case 5:
// Layout, item, pos and visibility. Set the item. // Layout, item, pos and visibility. Set the item.
osdConfigMutable()->item_pos[layout][item] = OSD_POS(col, row) | (visible ? OSD_VISIBLE_FLAG : 0); osdLayoutsConfigMutable()->item_pos[layout][item] = OSD_POS(col, row) | (visible ? OSD_VISIBLE_FLAG : 0);
break; break;
default: default:
// Unhandled // Unhandled
@ -3380,7 +3380,7 @@ static void printConfig(const char *cmdline, bool doDiff)
#ifdef USE_OSD #ifdef USE_OSD
cliPrintHashLine("osd_layout"); cliPrintHashLine("osd_layout");
printOsdLayout(dumpMask, &osdConfig_Copy, osdConfig(), -1, -1); printOsdLayout(dumpMask, &osdLayoutsConfig_Copy, osdLayoutsConfig(), -1, -1);
#endif #endif
cliPrintHashLine("master"); cliPrintHashLine("master");

View file

@ -1105,7 +1105,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, osdConfig()->dist_alarm); sbufWriteU16(dst, osdConfig()->dist_alarm);
sbufWriteU16(dst, osdConfig()->neg_alt_alarm); sbufWriteU16(dst, osdConfig()->neg_alt_alarm);
for (int i = 0; i < OSD_ITEM_COUNT; i++) { for (int i = 0; i < OSD_ITEM_COUNT; i++) {
sbufWriteU16(dst, osdConfig()->item_pos[0][i]); sbufWriteU16(dst, osdLayoutsConfig()->item_pos[0][i]);
} }
#else #else
sbufWriteU8(dst, OSD_DRIVER_NONE); // OSD not supported sbufWriteU8(dst, OSD_DRIVER_NONE); // OSD not supported
@ -2308,7 +2308,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
} else { } else {
// set a position setting // set a position setting
if ((dataSize >= 3) && (tmp_u8 < OSD_ITEM_COUNT)) // tmp_u8 == addr if ((dataSize >= 3) && (tmp_u8 < OSD_ITEM_COUNT)) // tmp_u8 == addr
osdConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src); osdLayoutsConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src);
else else
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
} }
@ -2755,7 +2755,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
if (!sbufReadU8Safe(&item, src)) { if (!sbufReadU8Safe(&item, src)) {
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
} }
if (!sbufReadU16Safe(&osdConfigMutable()->item_pos[layout][item], src)) { if (!sbufReadU16Safe(&osdLayoutsConfigMutable()->item_pos[layout][item], src)) {
return MSP_RESULT_ERROR; return MSP_RESULT_ERROR;
} }
// If the layout is not already overriden and it's different // If the layout is not already overriden and it's different
@ -3175,11 +3175,11 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
*ret = MSP_RESULT_ERROR; *ret = MSP_RESULT_ERROR;
break; break;
} }
sbufWriteU16(dst, osdConfig()->item_pos[layout][item]); sbufWriteU16(dst, osdLayoutsConfig()->item_pos[layout][item]);
} else { } else {
// Asking for an specific layout // Asking for an specific layout
for (unsigned ii = 0; ii < OSD_ITEM_COUNT; ii++) { for (unsigned ii = 0; ii < OSD_ITEM_COUNT; ii++) {
sbufWriteU16(dst, osdConfig()->item_pos[layout][ii]); sbufWriteU16(dst, osdLayoutsConfig()->item_pos[layout][ii]);
} }
} }
} else { } else {

View file

@ -199,7 +199,8 @@ static bool osdDisplayHasCanvas;
#define AH_SIDEBAR_WIDTH_POS 7 #define AH_SIDEBAR_WIDTH_POS 7
#define AH_SIDEBAR_HEIGHT_POS 3 #define AH_SIDEBAR_HEIGHT_POS 3
PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 12); PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 13);
PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0);
static int digitCount(int32_t value) static int digitCount(int32_t value)
{ {
@ -1264,7 +1265,7 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY,
static bool osdDrawSingleElement(uint8_t item) static bool osdDrawSingleElement(uint8_t item)
{ {
uint16_t pos = osdConfig()->item_pos[currentLayout][item]; uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item];
if (!OSD_VISIBLE(pos)) { if (!OSD_VISIBLE(pos)) {
return false; return false;
} }
@ -2603,197 +2604,199 @@ void osdDrawNextElement(void)
osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON); osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON);
} }
void pgResetFn_osdConfig(osdConfig_t *osdConfig) PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
{ .rssi_alarm = 20,
osdConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG; .time_alarm = 10,
osdConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG; .alt_alarm = 100,
osdConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1); .dist_alarm = 1000,
.neg_alt_alarm = 5,
osdConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; .current_alarm = 0,
//line 2 .imu_temp_alarm_min = -200,
osdConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); .imu_temp_alarm_max = 600,
osdConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); .esc_temp_alarm_min = -200,
osdConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); .esc_temp_alarm_max = 900,
osdConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); .gforce_alarm = 5,
osdConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); .gforce_axis_alarm_min = -5,
osdConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); .gforce_axis_alarm_max = 5,
osdConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2);
osdConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2);
osdConfig->item_pos[0][OSD_CRUISE_HEADING_ERROR] = OSD_POS(12, 2);
osdConfig->item_pos[0][OSD_CRUISE_HEADING_ADJUSTMENT] = OSD_POS(12, 2);
osdConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2);
osdConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5);
osdConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6);
osdConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7);
osdConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8);
osdConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5);
osdConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5);
osdConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7);
osdConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8);
// avoid OSD_VARIO under OSD_CROSSHAIRS
osdConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5);
// OSD_VARIO_NUM at the right of OSD_VARIO
osdConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7);
osdConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11);
osdConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2);
osdConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6);
osdConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8);
osdConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9);
osdConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12);
osdConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7);
osdConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6);
osdConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10);
osdConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12);
// Put this on top of the latitude, since it's very unlikely
// that users will want to use both at the same time.
osdConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12);
osdConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG;
osdConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12);
osdConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10);
osdConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11);
osdConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10);
osdConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11);
osdConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12);
osdConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1);
osdConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2);
osdConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10);
osdConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11);
osdConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5);
osdConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6);
osdConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7);
osdConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4);
osdConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5);
osdConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6);
osdConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7);
osdConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5);
#if defined(USE_ESC_SENSOR)
osdConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2);
osdConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3);
#endif
#if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE)
osdConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4);
#endif
// Under OSD_FLYMODE. TODO: Might not be visible on NTSC?
osdConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG;
for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) {
for (unsigned jj = 0; jj < ARRAYLEN(osdConfig->item_pos[0]); jj++) {
osdConfig->item_pos[ii][jj] = osdConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG;
}
}
osdConfig->rssi_alarm = 20;
osdConfig->time_alarm = 10;
osdConfig->alt_alarm = 100;
osdConfig->dist_alarm = 1000;
osdConfig->neg_alt_alarm = 5;
osdConfig->current_alarm = 0;
osdConfig->imu_temp_alarm_min = -200;
osdConfig->imu_temp_alarm_max = 600;
osdConfig->esc_temp_alarm_min = -200;
osdConfig->esc_temp_alarm_max = 900;
osdConfig->gforce_alarm = 5;
osdConfig->gforce_axis_alarm_min = -5;
osdConfig->gforce_axis_alarm_max = 5;
#ifdef USE_BARO #ifdef USE_BARO
osdConfig->baro_temp_alarm_min = -200; .baro_temp_alarm_min = -200,
osdConfig->baro_temp_alarm_max = 600; .baro_temp_alarm_max = 600,
#endif #endif
#ifdef USE_TEMPERATURE_SENSOR #ifdef USE_TEMPERATURE_SENSOR
osdConfig->temp_label_align = OSD_ALIGN_LEFT; .temp_label_align = OSD_ALIGN_LEFT,
#endif #endif
osdConfig->video_system = VIDEO_SYSTEM_AUTO; .video_system = VIDEO_SYSTEM_AUTO,
osdConfig->ahi_reverse_roll = 0; .ahi_reverse_roll = 0,
osdConfig->ahi_max_pitch = AH_MAX_PITCH_DEFAULT; .ahi_max_pitch = AH_MAX_PITCH_DEFAULT,
osdConfig->crosshairs_style = OSD_CROSSHAIRS_STYLE_DEFAULT; .crosshairs_style = OSD_CROSSHAIRS_STYLE_DEFAULT,
osdConfig->horizon_offset = 0; .horizon_offset = 0,
osdConfig->camera_uptilt = 0; .camera_uptilt = 0,
osdConfig->camera_fov_h = 135; .camera_fov_h = 135,
osdConfig->camera_fov_v = 85; .camera_fov_v = 85,
osdConfig->hud_margin_h = 3; .hud_margin_h = 3,
osdConfig->hud_margin_v = 3; .hud_margin_v = 3,
osdConfig->hud_homing = 0; .hud_homing = 0,
osdConfig->hud_homepoint = 0; .hud_homepoint = 0,
osdConfig->hud_radar_disp = 0; .hud_radar_disp = 0,
osdConfig->hud_radar_range_min = 3; .hud_radar_range_min = 3,
osdConfig->hud_radar_range_max = 4000; .hud_radar_range_max = 4000,
osdConfig->hud_radar_nearest = 0; .hud_radar_nearest = 0,
osdConfig->hud_wp_disp = 0; .hud_wp_disp = 0,
osdConfig->left_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE; .left_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE,
osdConfig->right_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE; .right_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE,
osdConfig->sidebar_scroll_arrows = 0; .sidebar_scroll_arrows = 0,
osdConfig->units = OSD_UNIT_METRIC; .units = OSD_UNIT_METRIC,
osdConfig->main_voltage_decimals = 1; .main_voltage_decimals = 1,
osdConfig->estimations_wind_compensation = true; .estimations_wind_compensation = true,
osdConfig->coordinate_digits = 9; .coordinate_digits = 9,
osdConfig->osd_failsafe_switch_layout = false; .osd_failsafe_switch_layout = false,
osdConfig->plus_code_digits = 11; .plus_code_digits = 11,
);
void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
{
osdLayoutsConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1);
osdLayoutsConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG;
//line 2
osdLayoutsConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1);
osdLayoutsConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2);
osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1);
osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1);
osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1);
osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1);
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2);
osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2);
osdLayoutsConfig->item_pos[0][OSD_CRUISE_HEADING_ERROR] = OSD_POS(12, 2);
osdLayoutsConfig->item_pos[0][OSD_CRUISE_HEADING_ADJUSTMENT] = OSD_POS(12, 2);
osdLayoutsConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2);
osdLayoutsConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5);
osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6);
osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7);
osdLayoutsConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8);
osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5);
osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5);
osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7);
osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8);
// avoid OSD_VARIO under OSD_CROSSHAIRS
osdLayoutsConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5);
// OSD_VARIO_NUM at the right of OSD_VARIO
osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7);
osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11);
osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2);
osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6);
osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8);
osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9);
osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12);
osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7);
osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6);
osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10);
osdLayoutsConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12);
// Put this on top of the latitude, since it's very unlikely
// that users will want to use both at the same time.
osdLayoutsConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12);
osdLayoutsConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG;
osdLayoutsConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12);
osdLayoutsConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10);
osdLayoutsConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11);
osdLayoutsConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10);
osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11);
osdLayoutsConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12);
osdLayoutsConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1);
osdLayoutsConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2);
osdLayoutsConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10);
osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11);
osdLayoutsConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5);
osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6);
osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7);
osdLayoutsConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4);
osdLayoutsConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5);
osdLayoutsConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6);
osdLayoutsConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7);
osdLayoutsConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5);
#if defined(USE_ESC_SENSOR)
osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2);
osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3);
#endif
#if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE)
osdLayoutsConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4);
#endif
// Under OSD_FLYMODE. TODO: Might not be visible on NTSC?
osdLayoutsConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG;
for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) {
for (unsigned jj = 0; jj < ARRAYLEN(osdLayoutsConfig->item_pos[0]); jj++) {
osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG;
}
}
} }
static void osdSetNextRefreshIn(uint32_t timeMs) { static void osdSetNextRefreshIn(uint32_t timeMs) {
@ -3288,7 +3291,7 @@ void osdStartFullRedraw(void)
void osdOverrideLayout(int layout, timeMs_t duration) void osdOverrideLayout(int layout, timeMs_t duration)
{ {
layoutOverride = constrain(layout, -1, ARRAYLEN(osdConfig()->item_pos) - 1); layoutOverride = constrain(layout, -1, ARRAYLEN(osdLayoutsConfig()->item_pos) - 1);
if (layoutOverride >= 0 && duration > 0) { if (layoutOverride >= 0 && duration > 0) {
layoutOverrideUntil = millis() + duration; layoutOverrideUntil = millis() + duration;
} else { } else {

View file

@ -194,10 +194,14 @@ typedef enum {
OSD_AHI_STYLE_LINE, OSD_AHI_STYLE_LINE,
} osd_ahi_style_e; } osd_ahi_style_e;
typedef struct osdConfig_s { typedef struct osdLayoutsConfig_s {
// Layouts // Layouts
uint16_t item_pos[OSD_LAYOUT_COUNT][OSD_ITEM_COUNT]; uint16_t item_pos[OSD_LAYOUT_COUNT][OSD_ITEM_COUNT];
} osdLayoutsConfig_t;
PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig);
typedef struct osdConfig_s {
// Alarms // Alarms
uint8_t rssi_alarm; // rssi % uint8_t rssi_alarm; // rssi %
uint16_t time_alarm; // fly minutes uint16_t time_alarm; // fly minutes

View file

@ -303,7 +303,7 @@ static void djiSerializeOSDConfigReply(sbuf_t *dst)
// Position & visibility encoded in 16 bits. Position encoding is the same between BF/DJI and INAV // Position & visibility encoded in 16 bits. Position encoding is the same between BF/DJI and INAV
// However visibility is different. INAV has 3 layouts, while BF only has visibility profiles // However visibility is different. INAV has 3 layouts, while BF only has visibility profiles
// Here we use only one OSD layout mapped to first OSD BF profile // Here we use only one OSD layout mapped to first OSD BF profile
uint16_t itemPos = osdConfig()->item_pos[0][inavOSDIdx]; uint16_t itemPos = osdLayoutsConfig()->item_pos[0][inavOSDIdx];
// Workarounds for certain OSD element positions // Workarounds for certain OSD element positions
// INAV calculates these dynamically, while DJI expects the config to have defined coordinates // INAV calculates these dynamically, while DJI expects the config to have defined coordinates