Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 30 additions & 0 deletions docs/Settings.md
Original file line number Diff line number Diff line change
Expand Up @@ -4762,6 +4762,36 @@ Number of decimals for the battery voltages displayed in the OSD [1-2].

---

### osd_map2d_hmargin

OSD 2D Map horizontal margin (on left and right, columns the map won't use for drawing)

| Default | Min | Max |
| --- | --- | --- |
| 5 | 0 | 15 |

---

### osd_map2d_ref_line_heading

OSD 2D Map reference line heading (0 is north, 90 east, 180 south and so on, -1 disabled). Requires using "up is north" map setting. The dashed line will be aligned to the heading set by this parameter. So should be set to the same heading as an easily recognizable and static feature nearby the place you are flying, for example a runway, a street, a fence, etc. Then you are able to compare the craft's position on the OSD map with this reference, making it easier to orientate yourself, align directional antennas and so on.

| Default | Min | Max |
| --- | --- | --- |
| -1 | -1 | 359 |

---

### osd_map2d_vmargin

OSD 2D Map vertical margin (on top and bottom, lines the map won't use for drawing)

| Default | Min | Max |
| --- | --- | --- |
| 3 | 0 | 10 |

---

### osd_msp_displayport_fullframe_interval

Full Frame redraw interval for MSP DisplayPort [deciseconds]. This is how often a full frame update is sent to the DisplayPort, to cut down on OSD artifacting. The default value should be fine for most pilots. Though long range pilots may benefit from increasing the refresh time, especially near the edge of range. -1 = disabled (legacy mode) | 0 = every frame (not recommended) | default = 10 (1 second)
Expand Down
22 changes: 21 additions & 1 deletion src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3742,7 +3742,27 @@ groups:
description: Show question marks where there is no symbol in the DJI font to represent the INAV OSD element's symbol. When off, blank spaces will be used. Only relevent for DJICOMPAT modes.
field: highlight_djis_missing_characters
default_value: ON
type: bool
type: bool
- name: osd_map2d_vmargin
description: OSD 2D Map vertical margin (on top and bottom, lines the map won't use for drawing)
field: map2d_vmargin
default_value: 3
min: 0
max: 10
- name: osd_map2d_hmargin
description: OSD 2D Map horizontal margin (on left and right, columns the map won't use for drawing)
field: map2d_hmargin
default_value: 5
min: 0
max: 15

- name: osd_map2d_ref_line_heading
description: OSD 2D Map reference line heading (0 is north, 90 east, 180 south and so on, -1 disabled). Requires using "up is north" map setting. The dashed line will be aligned to the heading set by this parameter. So should be set to the same heading as an easily recognizable and static feature nearby the place you are flying, for example a runway, a street, a fence, etc. Then you are able to compare the craft's position on the OSD map with this reference, making it easier to orientate yourself, align directional antennas and so on.
field: map2d_ref_line_heading
default_value: -1
min: -1
max: 359

- name: PG_OSD_COMMON_CONFIG
type: osdCommonConfig_t
headers: ["io/osd_common.h"]
Expand Down
57 changes: 51 additions & 6 deletions src/main/io/osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -1253,6 +1253,41 @@ int osdGetHeadingAngle(int angle)

#if defined(USE_GPS)

/* Draws a reference line in the center of screen, based on configurable heading (assuming north is up).
* Code borrowed and simplified from osdGridDrawArtificialHorizon(), since it's essentially the same thing
* as the artificial horizon line, but fixed on the same position and with roll only, no pitch.
*/
static void osdDrawMapReferenceLine(uint8_t midX, uint8_t midY)
{
float heading = osdConfig()->map2d_ref_line_heading;
float rollAngle = DEGREES_TO_RADIANS(90.f - (heading > 180.f ? heading - 180.f: heading));
const float ky = sin_approx(rollAngle);
const float kx = cos_approx(rollAngle);
const float ratio = osdDisplayIsPAL() ? 12.0f/15.0f : 12.0f/18.46f;

// Reduce the size so as not to be confused with the AHI, if both are used at the same time
static const uint8_t ref_line_width = OSD_AHI_WIDTH - 6U;
static const uint8_t ref_line_height = OSD_AHI_HEIGHT - 4U;

if (fabsf(ky) < fabsf(kx)) {
for (int8_t dx = -ref_line_width / 2; dx <= ref_line_width / 2; dx++) {
float fy = (ratio * dx) * (ky / kx) + 0.49f;
int8_t dy = floorf(fy);
const uint8_t chX = midX + dx, chY = midY - dy;
uint16_t c = SYM_AH_H_START + ((OSD_AHI_H_SYM_COUNT - 1) - (uint8_t)((fy - dy) * OSD_AHI_H_SYM_COUNT));
displayWriteChar(osdDisplayPort, chX, chY, c);
}
} else {
for (int8_t dy = -ref_line_height / 2; dy <= ref_line_height / 2; dy++) {
const float fx = (dy / ratio) * (kx / ky) + 0.5f;
const int8_t dx = floorf(fx);
const uint8_t chX = midX + dx, chY = midY - dy;
uint16_t c = SYM_AH_V_START + (fx - dx) * OSD_AHI_V_SYM_COUNT;
displayWriteChar(osdDisplayPort, chX, chY, c);
}
}
}

/* Draws a map with the given symbol in the center and given point of interest
* defined by its distance in meters and direction in degrees.
* referenceHeading indicates the up direction in the map, in degrees, while
Expand All @@ -1265,10 +1300,9 @@ static void osdDrawMap(int referenceHeading, uint16_t referenceSym, uint16_t cen
uint32_t poiDistance, int16_t poiDirection, uint16_t poiSymbol,
uint16_t *drawn, uint32_t *usedScale)
{
// TODO: These need to be tested with several setups. We might
// need to make them configurable.
const int hMargin = 5;
const int vMargin = 3;
// Configurable horizontal and vertical margins
const int hMargin = osdConfig()->map2d_hmargin;
const int vMargin = osdConfig()->map2d_vmargin;

// TODO: Get this from the display driver?
const int charWidth = 12;
Expand All @@ -1281,7 +1315,14 @@ static void osdDrawMap(int referenceHeading, uint16_t referenceSym, uint16_t cen
uint8_t midX = osdDisplayPort->cols / 2;
uint8_t midY = osdDisplayPort->rows / 2;

// Fixed marks
// Fixed marks
if(osdConfig()->map2d_ref_line_heading >= 0 && referenceSym == 'N') {
// Reference line is only drawn if enabled (ref heading == -1 disables it)
// and using North as the map reference
osdDrawMapReferenceLine(midX, midY);
}

// Draw the center symbol after the reference line so it overwrites the line center character
displayWriteChar(osdDisplayPort, midX, midY, centerSym);

// First, erase the previous drawing.
Expand Down Expand Up @@ -3952,7 +3993,11 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig,

.stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT,
.stats_page_auto_swap_time = SETTING_OSD_STATS_PAGE_AUTO_SWAP_TIME_DEFAULT,
.stats_show_metric_efficiency = SETTING_OSD_STATS_SHOW_METRIC_EFFICIENCY_DEFAULT
.stats_show_metric_efficiency = SETTING_OSD_STATS_SHOW_METRIC_EFFICIENCY_DEFAULT,

.map2d_vmargin = SETTING_OSD_MAP2D_VMARGIN_DEFAULT,
.map2d_hmargin = SETTING_OSD_MAP2D_HMARGIN_DEFAULT,
.map2d_ref_line_heading = SETTING_OSD_MAP2D_REF_LINE_HEADING_DEFAULT
);

void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
Expand Down
5 changes: 5 additions & 0 deletions src/main/io/osd.h
Original file line number Diff line number Diff line change
Expand Up @@ -460,11 +460,16 @@ typedef struct osdConfig_s {
#ifndef DISABLE_MSP_DJI_COMPAT
bool highlight_djis_missing_characters; // If enabled, show question marks where there is no character in DJI's font to represent an OSD element symbol
#endif

#ifdef USE_ADSB
uint16_t adsb_distance_warning; // in metres
uint16_t adsb_distance_alert; // in metres
uint16_t adsb_ignore_plane_above_me_limit; // in metres
#endif

uint8_t map2d_vmargin; // Vertical lines margin for 2D map (lines where nothing will be drawn)
uint8_t map2d_hmargin; // Horizontal lines margin for 2D map
int16_t map2d_ref_line_heading; // Reference line heading (0 to 360, -1 to disable)
} osdConfig_t;

PG_DECLARE(osdConfig_t, osdConfig);
Expand Down